diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/PeripheralPins.c b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/PeripheralPins.c
deleted file mode 100644
index 21944dcaa6..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/PeripheralPins.c
+++ /dev/null
@@ -1,156 +0,0 @@
-/***************************************************************************//**
- * @file PeripheralPins.c
- *******************************************************************************
- * @section License
- * (C) Copyright 2015 Silicon Labs, http://www.silabs.com
- *******************************************************************************
- *
- * 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.
- *
- ******************************************************************************/
-
-#include "PeripheralPins.h"
-#include "mbed_toolchain.h"
-
-/************ADC***************/
-MBED_WEAK const PinMap PinMap_ADC[] = {
-#ifdef ADC0_BASE
- {PD4, ADC_0, ADC_SINGLECTRL_INPUTSEL_CH4},
- {PD5, ADC_0, ADC_SINGLECTRL_INPUTSEL_CH5},
- {PD6, ADC_0, ADC_SINGLECTRL_INPUTSEL_CH6},
- {PD7, ADC_0, ADC_SINGLECTRL_INPUTSEL_CH7},
-#endif
- {NC , NC , NC}
-};
-
-/************I2C SCL***********/
-MBED_WEAK const PinMap PinMap_I2C_SCL[] = {
-#ifdef I2C0_BASE
- /* I2C0 */
- {PA1, I2C_0, 0},
- {PD7, I2C_0, 1},
- {PC1, I2C_0, 4},
- {PF1, I2C_0, 5},
- {PE13, I2C_0, 6},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-
-/************I2C SDA***********/
-MBED_WEAK const PinMap PinMap_I2C_SDA[] = {
-#ifdef I2C0_BASE
- /* I2C0 */
- {PA0, I2C_0, 0},
- {PD6, I2C_0, 1},
- {PC0, I2C_0, 4},
- {PF0, I2C_0, 5},
- {PE12, I2C_0, 6},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-/************PWM***************/
-MBED_WEAK const PinMap PinMap_PWM[] = {
-#if defined(TIMER_ROUTE_CC0PEN) || defined(TIMER_ROUTEPEN_CC0PEN)
- /* PWM0 */
- {PA0, PWM_CH0, 0},
-#endif
-#if defined(TIMER_ROUTE_CC1PEN) || defined(TIMER_ROUTEPEN_CC1PEN)
- /* PWM1 */
- {PA1, PWM_CH1, 0},
-#endif
-#if defined(TIMER_ROUTE_CC2PEN) || defined(TIMER_ROUTEPEN_CC2PEN)
- /* PWM2 */
- {PA2, PWM_CH2, 0},
-#endif
- {NC , NC , NC}
-};
-
-/*************SPI**************/
-MBED_WEAK const PinMap PinMap_SPI_MOSI[] = {
-#ifdef USART1_BASE
- /* USART1 */
- {PC0, SPI_1, 0},
- {PD7, SPI_1, 3},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-
-MBED_WEAK const PinMap PinMap_SPI_MISO[] = {
-#ifdef USART1_BASE
- /* USART1 */
- {PC1, SPI_1, 0},
- {PD6, SPI_1, 3},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-
-MBED_WEAK const PinMap PinMap_SPI_CLK[] = {
-#ifdef USART1_BASE
- /* USART1 */
- {PB7, SPI_1, 0},
- {PC15, SPI_1, 3},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-
-MBED_WEAK const PinMap PinMap_SPI_CS[] = {
-#ifdef USART1_BASE
- /* USART1 */
- {PB8, SPI_1, 0},
- {PC14, SPI_1, 3},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-
-/************UART**************/
-MBED_WEAK const PinMap PinMap_UART_TX[] = {
-#ifdef USART1_BASE
- /* USART1 */
- {PC0, USART_1, 0},
- {PD7, USART_1, 3},
-#endif
-#ifdef LEUART0_BASE
- /* LEUART0 */
- {PD4, LEUART_0, 0},
- {PB13, LEUART_0, 1},
- {PF0, LEUART_0, 3},
- {PF2, LEUART_0, 4},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
-
-MBED_WEAK const PinMap PinMap_UART_RX[] = {
-#ifdef USART1_BASE
- /* USART1 */
- {PC1, USART_1, 0},
- {PD6, USART_1, 3},
-#endif
-#ifdef LEUART0_BASE
- /* LEUART0 */
- {PD5, LEUART_0, 0},
- {PB14, LEUART_0, 1},
- {PF1, LEUART_0, 3},
- {PA0, LEUART_0, 4},
-#endif
- /* Not connected */
- {NC , NC , NC}
-};
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/TARGET_EFM32ZG_STK3200/PinNames.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/TARGET_EFM32ZG_STK3200/PinNames.h
deleted file mode 100644
index 818ba27b25..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/TARGET_EFM32ZG_STK3200/PinNames.h
+++ /dev/null
@@ -1,66 +0,0 @@
-/***************************************************************************//**
- * @file PinNames.h
- *******************************************************************************
- * @section License
- * (C) Copyright 2015 Silicon Labs, http://www.silabs.com
- *******************************************************************************
- *
- * 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.
- *
- ******************************************************************************/
-#ifndef MBED_PINNAMES_H
-#define MBED_PINNAMES_H
-
-#include "CommonPinNames.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- EFM32_STANDARD_PIN_DEFINITIONS,
-
- /* Starter Kit says LED0 and LED1, but mbed expects 1 and 2. This way using 1 and 2 or 0 and 1 will work. */
- LED0 = PC10,
- LED1 = PC11,
- LED2 = LED0,
- LED3 = LED0,
- LED4 = LED1,
-
- /* Push Buttons */
- SW0 = PC8,
- SW1 = PC9,
- BTN0 = SW0,
- BTN1 = SW1,
- // Standardized button names
- BUTTON1 = BTN0,
- BUTTON2 = BTN1,
-
- /* Serial */
- SERIAL_TX = PD7,
- SERIAL_RX = PD6,
- USBTX = PD4,
- USBRX = PD5,
-
- /* Board Controller */
- STDIO_UART_TX = USBTX,
- STDIO_UART_RX = USBRX
-} PinName;
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/TARGET_EFM32ZG_STK3200/device_peripherals.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/TARGET_EFM32ZG_STK3200/device_peripherals.h
deleted file mode 100644
index 9fc97dce33..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/TARGET_EFM32ZG_STK3200/device_peripherals.h
+++ /dev/null
@@ -1,36 +0,0 @@
-/***************************************************************************//**
- * @file device_peripheral.h
- *******************************************************************************
- * @section License
- * (C) Copyright 2015 Silicon Labs, http://www.silabs.com
- *******************************************************************************
- *
- * 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.
- *
- ******************************************************************************/
-#ifndef MBED_DEVICE_PERIPHERALS_H
-#define MBED_DEVICE_PERIPHERALS_H
-
-/* us ticker */
-#define US_TICKER_TIMER TIMER1
-#define US_TICKER_TIMER_CLOCK cmuClock_TIMER1
-#define US_TICKER_TIMER_IRQ TIMER1_IRQn
-
-/* PWM */
-#define PWM_TIMER TIMER0
-#define PWM_TIMER_CLOCK cmuClock_TIMER0
-#define PWM_ROUTE TIMER_ROUTE_LOCATION_LOC0
-
-#endif
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_ARM_MICRO/efm32zg.sct b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_ARM_MICRO/efm32zg.sct
deleted file mode 100644
index f4a89f7688..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_ARM_MICRO/efm32zg.sct
+++ /dev/null
@@ -1,48 +0,0 @@
-#! armcc -E
-; *************************************************************
-; *** Scatter-Loading Description File generated by uVision ***
-; *************************************************************
-
-#if !defined(MBED_APP_START)
- #define MBED_APP_START 0x00000000
-#endif
-
-#if !defined(MBED_APP_SIZE)
- #define MBED_APP_SIZE 0x00008000
-#endif
-
-#if !defined(MBED_RAM_START)
- #define MBED_RAM_START 0x20000000
-#endif
-
-#if !defined(MBED_RAM_SIZE)
- #define MBED_RAM_SIZE 0x00001000
-#endif
-
-
-#if !defined(MBED_BOOT_STACK_SIZE)
- #define MBED_BOOT_STACK_SIZE 0x400
-#endif
-
-#define VECTOR_SIZE 0x90
-
-#define RAM_FIXED_SIZE (MBED_BOOT_STACK_SIZE+VECTOR_SIZE)
-
-LR_IROM1 MBED_APP_START MBED_APP_SIZE { ; load region size_region
-
- ER_IROM1 MBED_APP_START MBED_APP_SIZE { ; load address = execution address
- *.o (RESET, +First)
- *(InRoot$$Sections)
- .ANY (+RO)
- }
-
- RW_IRAM1 (MBED_RAM_START+VECTOR_SIZE) (MBED_RAM_SIZE-VECTOR_SIZE) { ; RW data
- .ANY (+RW +ZI)
- }
-
- ARM_LIB_HEAP AlignExpr(+0, 16) EMPTY (MBED_RAM_SIZE-RAM_FIXED_SIZE+MBED_RAM_START-AlignExpr(ImageLimit(RW_IRAM1), 16)) {
- }
-
- ARM_LIB_STACK (MBED_RAM_START+MBED_RAM_SIZE) EMPTY -MBED_BOOT_STACK_SIZE { ; stack
- }
-}
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_ARM_MICRO/startup_efm32zg.S b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_ARM_MICRO/startup_efm32zg.S
deleted file mode 100644
index 62b5bd047b..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_ARM_MICRO/startup_efm32zg.S
+++ /dev/null
@@ -1,163 +0,0 @@
-;/**************************************************************************//**
-; * @file startup_efm32zg.s
-; * @brief CMSIS Core Device Startup File for
-; * Silicon Labs EFM32ZG Device Series
-; * @version 4.2.1
-; * @date 03. February 2012
-; *
-; * @note
-; * Copyright (C) 2012 ARM Limited. All rights reserved.
-; *
-; * @par
-; * ARM Limited (ARM) is supplying this software for use with Cortex-M
-; * processor based microcontrollers. This file can be freely distributed
-; * within development tools that are supporting such ARM based processors.
-; *
-; * @par
-; * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
-; * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
-; * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
-; * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
-; * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
-; *
-; ******************************************************************************/
-
-
- PRESERVE8
- THUMB
-
-
-; Vector Table Mapped to Address 0 at Reset
-
- AREA RESET, DATA, READONLY, ALIGN=8
- EXPORT __Vectors
- EXPORT __Vectors_End
- EXPORT __Vectors_Size
- IMPORT |Image$$ARM_LIB_STACK$$ZI$$Limit|
-
-__Vectors DCD |Image$$ARM_LIB_STACK$$ZI$$Limit| ; Top of Stack
- DCD Reset_Handler ; Reset Handler
- DCD NMI_Handler ; NMI Handler
- DCD HardFault_Handler ; Hard Fault Handler
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD SVC_Handler ; SVCall Handler
- DCD 0 ; Reserved
- DCD 0 ; Reserved
- DCD PendSV_Handler ; PendSV Handler
- DCD SysTick_Handler ; SysTick Handler
-
- ; External Interrupts
-
- DCD DMA_IRQHandler ; 0: DMA Interrupt
- DCD GPIO_EVEN_IRQHandler ; 1: GPIO_EVEN Interrupt
- DCD TIMER0_IRQHandler ; 2: TIMER0 Interrupt
- DCD ACMP0_IRQHandler ; 3: ACMP0 Interrupt
- DCD ADC0_IRQHandler ; 4: ADC0 Interrupt
- DCD I2C0_IRQHandler ; 5: I2C0 Interrupt
- DCD GPIO_ODD_IRQHandler ; 6: GPIO_ODD Interrupt
- DCD TIMER1_IRQHandler ; 7: TIMER1 Interrupt
- DCD USART1_RX_IRQHandler ; 8: USART1_RX Interrupt
- DCD USART1_TX_IRQHandler ; 9: USART1_TX Interrupt
- DCD LEUART0_IRQHandler ; 10: LEUART0 Interrupt
- DCD PCNT0_IRQHandler ; 11: PCNT0 Interrupt
- DCD RTC_IRQHandler ; 12: RTC Interrupt
- DCD CMU_IRQHandler ; 13: CMU Interrupt
- DCD VCMP_IRQHandler ; 14: VCMP Interrupt
- DCD MSC_IRQHandler ; 15: MSC Interrupt
- DCD AES_IRQHandler ; 16: AES Interrupt
- DCD 0 ; 17: Reserved
- DCD 0 ; 18: Reserved
-
-__Vectors_End
-__Vectors_Size EQU __Vectors_End - __Vectors
-
- AREA |.text|, CODE, READONLY
-
-
-; Reset Handler
-
-Reset_Handler PROC
- EXPORT Reset_Handler [WEAK]
- IMPORT SystemInit
- IMPORT __main
- LDR R0, =SystemInit
- BLX R0
- LDR R0, =__main
- BX R0
- ENDP
-
-
-; Dummy Exception Handlers (infinite loops which can be modified)
-
-NMI_Handler PROC
- EXPORT NMI_Handler [WEAK]
- B .
- ENDP
-HardFault_Handler\
- PROC
- EXPORT HardFault_Handler [WEAK]
- B .
- ENDP
-SVC_Handler PROC
- EXPORT SVC_Handler [WEAK]
- B .
- ENDP
-PendSV_Handler PROC
- EXPORT PendSV_Handler [WEAK]
- B .
- ENDP
-SysTick_Handler PROC
- EXPORT SysTick_Handler [WEAK]
- B .
- ENDP
-
-Default_Handler PROC
- EXPORT DMA_IRQHandler [WEAK]
- EXPORT GPIO_EVEN_IRQHandler [WEAK]
- EXPORT TIMER0_IRQHandler [WEAK]
- EXPORT ACMP0_IRQHandler [WEAK]
- EXPORT ADC0_IRQHandler [WEAK]
- EXPORT I2C0_IRQHandler [WEAK]
- EXPORT GPIO_ODD_IRQHandler [WEAK]
- EXPORT TIMER1_IRQHandler [WEAK]
- EXPORT USART1_RX_IRQHandler [WEAK]
- EXPORT USART1_TX_IRQHandler [WEAK]
- EXPORT LEUART0_IRQHandler [WEAK]
- EXPORT PCNT0_IRQHandler [WEAK]
- EXPORT RTC_IRQHandler [WEAK]
- EXPORT CMU_IRQHandler [WEAK]
- EXPORT VCMP_IRQHandler [WEAK]
- EXPORT MSC_IRQHandler [WEAK]
- EXPORT AES_IRQHandler [WEAK]
-
-
-DMA_IRQHandler
-GPIO_EVEN_IRQHandler
-TIMER0_IRQHandler
-ACMP0_IRQHandler
-ADC0_IRQHandler
-I2C0_IRQHandler
-GPIO_ODD_IRQHandler
-TIMER1_IRQHandler
-USART1_RX_IRQHandler
-USART1_TX_IRQHandler
-LEUART0_IRQHandler
-PCNT0_IRQHandler
-RTC_IRQHandler
-CMU_IRQHandler
-VCMP_IRQHandler
-MSC_IRQHandler
-AES_IRQHandler
-
- B .
- ENDP
-
- ALIGN
-
- END
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_GCC_ARM/efm32zg.ld b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_GCC_ARM/efm32zg.ld
deleted file mode 100644
index 0705cf64b2..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_GCC_ARM/efm32zg.ld
+++ /dev/null
@@ -1,231 +0,0 @@
-/* Linker script for Silicon Labs EFM32ZG devices */
-/* */
-/* This file is subject to the license terms as defined in ARM's */
-/* CMSIS END USER LICENSE AGREEMENT.pdf, governing the use of */
-/* Example Code. */
-/* */
-/* Silicon Laboratories, Inc. 2015 */
-/* */
-/* Version 4.2.0 */
-/* */
-
-#if !defined(MBED_APP_START)
- #define MBED_APP_START 0x00000000
-#endif
-
-#if !defined(MBED_APP_SIZE)
- #define MBED_APP_SIZE 32768
-#endif
-
-#if !defined(MBED_BOOT_STACK_SIZE)
- #define MBED_BOOT_STACK_SIZE 0x400
-#endif
-
-STACK_SIZE = MBED_BOOT_STACK_SIZE;
-
-MEMORY
-{
- FLASH (rx) : ORIGIN = MBED_APP_START, LENGTH = MBED_APP_SIZE
- RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 4096
-}
-
-/* MBED: mbed needs to be able to dynamically set the interrupt vector table.
- * We make room for the table at the very beginning of RAM, i.e. at
- * 0x20000000. We need (16+19) * sizeof(uint32_t) = 140 + 4(8-byte aligned) bytes for EFM32ZG */
-__vector_size = 0x90;
-
-/* Linker script to place sections and symbol values. Should be used together
- * with other linker script that defines memory regions FLASH and RAM.
- * It references following symbols, which must be defined in code:
- * Reset_Handler : Entry of reset handler
- *
- * It defines following symbols, which code can use without definition:
- * __exidx_start
- * __exidx_end
- * __copy_table_start__
- * __copy_table_end__
- * __zero_table_start__
- * __zero_table_end__
- * __etext
- * __data_start__
- * __preinit_array_start
- * __preinit_array_end
- * __init_array_start
- * __init_array_end
- * __fini_array_start
- * __fini_array_end
- * __data_end__
- * __bss_start__
- * __bss_end__
- * __end__
- * end
- * __HeapLimit
- * __StackLimit
- * __StackTop
- * __stack
- * __Vectors_End
- * __Vectors_Size
- */
-ENTRY(Reset_Handler)
-
-SECTIONS
-{
- .text :
- {
- KEEP(*(.vectors))
- __Vectors_End = .;
- __Vectors_Size = __Vectors_End - __Vectors;
- __end__ = .;
-
- *(.text*)
-
- KEEP(*(.init))
- KEEP(*(.fini))
-
- /* .ctors */
- *crtbegin.o(.ctors)
- *crtbegin?.o(.ctors)
- *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
- *(SORT(.ctors.*))
- *(.ctors)
-
- /* .dtors */
- *crtbegin.o(.dtors)
- *crtbegin?.o(.dtors)
- *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
- *(SORT(.dtors.*))
- *(.dtors)
-
- *(.rodata*)
-
- KEEP(*(.eh_frame*))
- } > FLASH
-
- .ARM.extab :
- {
- *(.ARM.extab* .gnu.linkonce.armextab.*)
- } > FLASH
-
- __exidx_start = .;
- .ARM.exidx :
- {
- *(.ARM.exidx* .gnu.linkonce.armexidx.*)
- } > FLASH
- __exidx_end = .;
-
- /* To copy multiple ROM to RAM sections,
- * uncomment .copy.table section and,
- * define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */
- /*
- .copy.table :
- {
- . = ALIGN(8);
- __copy_table_start__ = .;
- LONG (__etext)
- LONG (__data_start__)
- LONG (__data_end__ - __data_start__)
- LONG (__etext2)
- LONG (__data2_start__)
- LONG (__data2_end__ - __data2_start__)
- __copy_table_end__ = .;
- } > FLASH
- */
-
- /* To clear multiple BSS sections,
- * uncomment .zero.table section and,
- * define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */
- /*
- .zero.table :
- {
- . = ALIGN(8);
- __zero_table_start__ = .;
- LONG (__bss_start__)
- LONG (__bss_end__ - __bss_start__)
- LONG (__bss2_start__)
- LONG (__bss2_end__ - __bss2_start__)
- __zero_table_end__ = .;
- } > FLASH
- */
-
- __etext = .;
-
- .data : AT (__etext)
- {
- __data_start__ = .;
- *("dma")
- PROVIDE( __start_vector_table__ = .);
- . += __vector_size;
- PROVIDE( __end_vector_table__ = .);
- *(vtable)
- *(.data*)
- . = ALIGN (8);
- *(.ram)
-
- . = ALIGN(8);
- /* preinit data */
- PROVIDE_HIDDEN (__preinit_array_start = .);
- KEEP(*(.preinit_array))
- PROVIDE_HIDDEN (__preinit_array_end = .);
-
- . = ALIGN(8);
- /* init data */
- PROVIDE_HIDDEN (__init_array_start = .);
- KEEP(*(SORT(.init_array.*)))
- KEEP(*(.init_array))
- PROVIDE_HIDDEN (__init_array_end = .);
-
- . = ALIGN(8);
- /* finit data */
- PROVIDE_HIDDEN (__fini_array_start = .);
- KEEP(*(SORT(.fini_array.*)))
- KEEP(*(.fini_array))
- PROVIDE_HIDDEN (__fini_array_end = .);
-
- KEEP(*(.jcr*))
- . = ALIGN(8);
- /* All data end */
- __data_end__ = .;
-
- } > RAM
-
- .bss :
- {
- . = ALIGN(8);
- __bss_start__ = .;
- *(.bss*)
- *(COMMON)
- . = ALIGN(8);
- __bss_end__ = .;
- } > RAM
-
- .heap (COPY):
- {
- __HeapBase = .;
- __end__ = .;
- end = __end__;
- _end = __end__;
- KEEP(*(.heap*))
- . = ORIGIN(RAM) + LENGTH(RAM) - STACK_SIZE;
- __HeapLimit = .;
- } > RAM
-
- /* .stack_dummy section doesn't contains any symbols. It is only
- * used for linker to calculate size of stack sections, and assign
- * values to stack symbols later */
- .stack_dummy (COPY):
- {
- KEEP(*(.stack*))
- } > RAM
-
- /* Set stack top to end of RAM, and stack limit move down by
- * size of stack_dummy section */
- __StackTop = ORIGIN(RAM) + LENGTH(RAM);
- __StackLimit = __StackTop - STACK_SIZE;
- PROVIDE(__stack = __StackTop);
-
- /* Check if data + heap + stack exceeds RAM limit */
- ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
-
- /* Check if FLASH usage exceeds FLASH size */
- ASSERT( LENGTH(FLASH) >= (__etext + SIZEOF(.data)), "FLASH memory overflowed !")
-}
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_GCC_ARM/startup_efm32zg.S b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_GCC_ARM/startup_efm32zg.S
deleted file mode 100644
index 704fa35a1f..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_GCC_ARM/startup_efm32zg.S
+++ /dev/null
@@ -1,303 +0,0 @@
-/* @file startup_efm32zg.S
- * @brief startup file for Silicon Labs EFM32ZG devices.
- * For use with GCC for ARM Embedded Processors
- * @version 4.2.1
- * Date: 12 June 2014
- *
- */
-/* Copyright (c) 2011 - 2014 ARM LIMITED
-
- All rights reserved.
- Redistribution and use in source and binary forms, with or without
- modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - Redistributions in binary form must reproduce the above copyright
- notice, this list of conditions and the following disclaimer in the
- documentation and/or other materials provided with the distribution.
- - Neither the name of ARM nor the names of its contributors may be used
- to endorse or promote products derived from this software without
- specific prior written permission.
- *
- THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
- LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- POSSIBILITY OF SUCH DAMAGE.
- ---------------------------------------------------------------------------*/
-
- .syntax unified
- .arch armv6-m
-
- .section .stack
- .align 3
-#ifdef __STACK_SIZE
- .equ Stack_Size, __STACK_SIZE
-#else
- .equ Stack_Size, 0x00000400
-#endif
- .globl __StackTop
- .globl __StackLimit
-__StackLimit:
- .space Stack_Size
- .size __StackLimit, . - __StackLimit
-__StackTop:
- .size __StackTop, . - __StackTop
-
- .section .heap
- .align 3
-#ifdef __HEAP_SIZE
- .equ Heap_Size, __HEAP_SIZE
-#else
- .equ Heap_Size, 0x00000000
-#endif
- .globl __HeapBase
- .globl __HeapLimit
-__HeapBase:
- .if Heap_Size
- .space Heap_Size
- .endif
- .size __HeapBase, . - __HeapBase
-__HeapLimit:
- .size __HeapLimit, . - __HeapLimit
-
- .section .vectors
- .align 2
- .globl __Vectors
-__Vectors:
- .long __StackTop /* Top of Stack */
- .long Reset_Handler /* Reset Handler */
- .long NMI_Handler /* NMI Handler */
- .long HardFault_Handler /* Hard Fault Handler */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long SVC_Handler /* SVCall Handler */
- .long Default_Handler /* Reserved */
- .long Default_Handler /* Reserved */
- .long PendSV_Handler /* PendSV Handler */
- .long SysTick_Handler /* SysTick Handler */
-
- /* External interrupts */
-
- .long DMA_IRQHandler /* 0 - DMA */
- .long GPIO_EVEN_IRQHandler /* 1 - GPIO_EVEN */
- .long TIMER0_IRQHandler /* 2 - TIMER0 */
- .long ACMP0_IRQHandler /* 3 - ACMP0 */
- .long ADC0_IRQHandler /* 4 - ADC0 */
- .long I2C0_IRQHandler /* 5 - I2C0 */
- .long GPIO_ODD_IRQHandler /* 6 - GPIO_ODD */
- .long TIMER1_IRQHandler /* 7 - TIMER1 */
- .long USART1_RX_IRQHandler /* 8 - USART1_RX */
- .long USART1_TX_IRQHandler /* 9 - USART1_TX */
- .long LEUART0_IRQHandler /* 10 - LEUART0 */
- .long PCNT0_IRQHandler /* 11 - PCNT0 */
- .long RTC_IRQHandler /* 12 - RTC */
- .long CMU_IRQHandler /* 13 - CMU */
- .long VCMP_IRQHandler /* 14 - VCMP */
- .long MSC_IRQHandler /* 15 - MSC */
- .long AES_IRQHandler /* 16 - AES */
- .long Default_Handler /* 17 - Reserved */
- .long Default_Handler /* 18 - Reserved */
-
-
- .size __Vectors, . - __Vectors
-
- .text
- .thumb
- .thumb_func
- .align 2
- .globl Reset_Handler
- .type Reset_Handler, %function
-Reset_Handler:
-#ifndef __NO_SYSTEM_INIT
- ldr r0, =SystemInit
- blx r0
-#endif
-
-/* Firstly it copies data from read only memory to RAM. There are two schemes
- * to copy. One can copy more than one sections. Another can only copy
- * one section. The former scheme needs more instructions and read-only
- * data to implement than the latter.
- * Macro __STARTUP_COPY_MULTIPLE is used to choose between two schemes. */
-
-#ifdef __STARTUP_COPY_MULTIPLE
-/* Multiple sections scheme.
- *
- * Between symbol address __copy_table_start__ and __copy_table_end__,
- * there are array of triplets, each of which specify:
- * offset 0: LMA of start of a section to copy from
- * offset 4: VMA of start of a section to copy to
- * offset 8: size of the section to copy. Must be multiply of 4
- *
- * All addresses must be aligned to 4 bytes boundary.
- */
- ldr r4, =__copy_table_start__
- ldr r5, =__copy_table_end__
-
-.L_loop0:
- cmp r4, r5
- bge .L_loop0_done
- ldr r1, [r4]
- ldr r2, [r4, #4]
- ldr r3, [r4, #8]
-
-.L_loop0_0:
- subs r3, #4
- blt .L_loop0_0_done
- ldr r0, [r1, r3]
- str r0, [r2, r3]
- b .L_loop0_0
-
-.L_loop0_0_done:
- adds r4, #12
- b .L_loop0
-
-.L_loop0_done:
-#else
-/* Single section scheme.
- *
- * The ranges of copy from/to are specified by following symbols
- * __etext: LMA of start of the section to copy from. Usually end of text
- * __data_start__: VMA of start of the section to copy to
- * __data_end__: VMA of end of the section to copy to
- *
- * All addresses must be aligned to 4 bytes boundary.
- */
- ldr r1, =__etext
- ldr r2, =__data_start__
- ldr r3, =__data_end__
-
- subs r3, r2
- ble .L_loop1_done
-
-.L_loop1:
- subs r3, #4
- ldr r0, [r1,r3]
- str r0, [r2,r3]
- bgt .L_loop1
-
-.L_loop1_done:
-#endif /*__STARTUP_COPY_MULTIPLE */
-
-/* This part of work usually is done in C library startup code. Otherwise,
- * define this macro to enable it in this startup.
- *
- * There are two schemes too. One can clear multiple BSS sections. Another
- * can only clear one section. The former is more size expensive than the
- * latter.
- *
- * Define macro __STARTUP_CLEAR_BSS_MULTIPLE to choose the former.
- * Otherwise efine macro __STARTUP_CLEAR_BSS to choose the later.
- */
-#ifdef __STARTUP_CLEAR_BSS_MULTIPLE
-/* Multiple sections scheme.
- *
- * Between symbol address __copy_table_start__ and __copy_table_end__,
- * there are array of tuples specifying:
- * offset 0: Start of a BSS section
- * offset 4: Size of this BSS section. Must be multiply of 4
- */
- ldr r3, =__zero_table_start__
- ldr r4, =__zero_table_end__
-
-.L_loop2:
- cmp r3, r4
- bge .L_loop2_done
- ldr r1, [r3]
- ldr r2, [r3, #4]
- movs r0, 0
-
-.L_loop2_0:
- subs r2, #4
- blt .L_loop2_0_done
- str r0, [r1, r2]
- b .L_loop2_0
-.L_loop2_0_done:
-
- adds r3, #8
- b .L_loop2
-.L_loop2_done:
-#elif defined (__STARTUP_CLEAR_BSS)
-/* Single BSS section scheme.
- *
- * The BSS section is specified by following symbols
- * __bss_start__: start of the BSS section.
- * __bss_end__: end of the BSS section.
- *
- * Both addresses must be aligned to 4 bytes boundary.
- */
- ldr r1, =__bss_start__
- ldr r2, =__bss_end__
-
- movs r0, 0
- subs r2, r1
- ble .L_loop3_done
-
-.L_loop3:
- subs r2, #4
- str r0, [r1, r2]
- bgt .L_loop3
-.L_loop3_done:
-#endif /* __STARTUP_CLEAR_BSS_MULTIPLE || __STARTUP_CLEAR_BSS */
-
-#ifndef __START
-#define __START _start
-#endif
- bl __START
-
- .pool
- .size Reset_Handler, . - Reset_Handler
-
- .align 1
- .thumb_func
- .weak Default_Handler
- .type Default_Handler, %function
-Default_Handler:
- b .
- .size Default_Handler, . - Default_Handler
-
-/* Macro to define default handlers. Default handler
- * will be weak symbol and just dead loops. They can be
- * overwritten by other handlers */
- .macro def_irq_handler handler_name
- .weak \handler_name
- .set \handler_name, Default_Handler
- .endm
-
- def_irq_handler NMI_Handler
- def_irq_handler HardFault_Handler
- def_irq_handler SVC_Handler
- def_irq_handler PendSV_Handler
- def_irq_handler SysTick_Handler
-
- def_irq_handler DMA_IRQHandler
- def_irq_handler GPIO_EVEN_IRQHandler
- def_irq_handler TIMER0_IRQHandler
- def_irq_handler ACMP0_IRQHandler
- def_irq_handler ADC0_IRQHandler
- def_irq_handler I2C0_IRQHandler
- def_irq_handler GPIO_ODD_IRQHandler
- def_irq_handler TIMER1_IRQHandler
- def_irq_handler USART1_RX_IRQHandler
- def_irq_handler USART1_TX_IRQHandler
- def_irq_handler LEUART0_IRQHandler
- def_irq_handler PCNT0_IRQHandler
- def_irq_handler RTC_IRQHandler
- def_irq_handler CMU_IRQHandler
- def_irq_handler VCMP_IRQHandler
- def_irq_handler MSC_IRQHandler
- def_irq_handler AES_IRQHandler
-
-
- .end
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_IAR/efm32zg222f32.icf b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_IAR/efm32zg222f32.icf
deleted file mode 100644
index ae582b33f3..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_IAR/efm32zg222f32.icf
+++ /dev/null
@@ -1,37 +0,0 @@
-/*###ICF### Section handled by ICF editor, don't touch! ****/
-/*-Editor annotation file-*/
-/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */
-
-if (!isdefinedsymbol(MBED_APP_START)) { define symbol MBED_APP_START = 0x00000000; }
-if (!isdefinedsymbol(MBED_APP_SIZE)) { define symbol MBED_APP_SIZE = 0x00008000; }
-if (!isdefinedsymbol(MBED_BOOT_STACK_SIZE)) { define symbol MBED_BOOT_STACK_SIZE = 0x400; }
-
-/*-Specials-*/
-define symbol __ICFEDIT_intvec_start__ = MBED_APP_START;
-/*-Memory Regions-*/
-define symbol __ICFEDIT_region_ROM_start__ = MBED_APP_START;
-define symbol __ICFEDIT_region_ROM_end__ = MBED_APP_START + MBED_APP_SIZE - 1;
-define symbol __NVIC_start__ = 0x20000000;
-define symbol __NVIC_end__ = 0x2000008F;
-define symbol __ICFEDIT_region_RAM_start__ = 0x20000090;
-define symbol __ICFEDIT_region_RAM_end__ = 0x20000FFF;
-/*-Sizes-*/
-define symbol __ICFEDIT_size_cstack__ = MBED_BOOT_STACK_SIZE;
-define symbol __ICFEDIT_size_heap__ = 0x400;
-/**** End of ICF editor section. ###ICF###*/
-
-define memory mem with size = 4G;
-define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__];
-define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__];
-
-define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
-define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { };
-
-initialize by copy { readwrite };
-do not initialize { section .noinit };
-
-keep { section .intvec };
-place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
-place in ROM_region { readonly };
-place in RAM_region { readwrite, block CSTACK, block HEAP };
-
\ No newline at end of file
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_IAR/startup_efm32zg.S b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_IAR/startup_efm32zg.S
deleted file mode 100644
index 19098da108..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/TARGET_32K/TOOLCHAIN_IAR/startup_efm32zg.S
+++ /dev/null
@@ -1,235 +0,0 @@
-;/**************************************************************************//**
-; * @file startup_efm32zg.s
-; * @brief CMSIS Core Device Startup File
-; * Silicon Labs EFM32ZG Device Series
-; * @version 5.0.0
-; * @date 30. January 2012
-; *
-; * @note
-; * Copyright (C) 2012 ARM Limited. All rights reserved.
-; *
-; * @par
-; * ARM Limited (ARM) is supplying this software for use with Cortex-M
-; * processor based microcontrollers. This file can be freely distributed
-; * within development tools that are supporting such ARM based processors.
-; *
-; * @par
-; * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
-; * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
-; * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
-; * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
-; * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
-; *
-; ******************************************************************************/
-
-;
-; The modules in this file are included in the libraries, and may be replaced
-; by any user-defined modules that define the PUBLIC symbol _program_start or
-; a user defined start symbol.
-; To override the cstartup defined in the library, simply add your modified
-; version to the workbench project.
-;
-; The vector table is normally located at address 0.
-;
-; When debugging in RAM, it can be located in RAM with at least a 128 byte
-; alignment, 256 byte alignment is requied if all interrupt vectors are in use.
-;
-; The name "__vector_table" has special meaning for C-SPY:
-; it is where the SP start value is found, and the NVIC vector
-; table register (VTOR) is initialized to this address if != 0.
-;
-; Cortex-M version
-;
- MODULE ?cstartup
-
- ;; Forward declaration of sections.
- SECTION CSTACK:DATA:NOROOT(3)
-
- SECTION .intvec:CODE:NOROOT(8)
-
- EXTERN __iar_program_start
- EXTERN SystemInit
- PUBLIC __vector_table
- PUBLIC __vector_table_0x1c
- PUBLIC __Vectors
- PUBLIC __Vectors_End
- PUBLIC __Vectors_Size
-
- DATA
-
-__vector_table
- DCD sfe(CSTACK)
- DCD Reset_Handler
-
- DCD NMI_Handler
- DCD HardFault_Handler
- DCD 0
- DCD 0
- DCD 0
-__vector_table_0x1c
- DCD 0
- DCD 0
- DCD 0
- DCD 0
- DCD SVC_Handler
- DCD 0
- DCD 0
- DCD PendSV_Handler
- DCD SysTick_Handler
-
- ; External Interrupts
-
- DCD DMA_IRQHandler ; 0: DMA Interrupt
- DCD GPIO_EVEN_IRQHandler ; 1: GPIO_EVEN Interrupt
- DCD TIMER0_IRQHandler ; 2: TIMER0 Interrupt
- DCD ACMP0_IRQHandler ; 3: ACMP0 Interrupt
- DCD ADC0_IRQHandler ; 4: ADC0 Interrupt
- DCD I2C0_IRQHandler ; 5: I2C0 Interrupt
- DCD GPIO_ODD_IRQHandler ; 6: GPIO_ODD Interrupt
- DCD TIMER1_IRQHandler ; 7: TIMER1 Interrupt
- DCD USART1_RX_IRQHandler ; 8: USART1_RX Interrupt
- DCD USART1_TX_IRQHandler ; 9: USART1_TX Interrupt
- DCD LEUART0_IRQHandler ; 10: LEUART0 Interrupt
- DCD PCNT0_IRQHandler ; 11: PCNT0 Interrupt
- DCD RTC_IRQHandler ; 12: RTC Interrupt
- DCD CMU_IRQHandler ; 13: CMU Interrupt
- DCD VCMP_IRQHandler ; 14: VCMP Interrupt
- DCD MSC_IRQHandler ; 15: MSC Interrupt
- DCD AES_IRQHandler ; 16: AES Interrupt
- DCD 0 ; 17: Reserved Interrupt
- DCD 0 ; 18: Reserved Interrupt
-
-
-__Vectors_End
-__Vectors EQU __vector_table
-__Vectors_Size EQU __Vectors_End - __Vectors
-
-
-;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
-;;
-;; Default interrupt handlers.
-;;
- THUMB
-
- PUBWEAK Reset_Handler
- SECTION .text:CODE:REORDER:NOROOT(2)
-Reset_Handler
- LDR R0, =SystemInit
- BLX R0
- LDR R0, =__iar_program_start
- BX R0
-
- PUBWEAK NMI_Handler
- SECTION .text:CODE:REORDER:NOROOT(1)
-NMI_Handler
- B NMI_Handler
-
- PUBWEAK HardFault_Handler
- SECTION .text:CODE:REORDER:NOROOT(1)
-HardFault_Handler
- B HardFault_Handler
-
- PUBWEAK SVC_Handler
- SECTION .text:CODE:REORDER:NOROOT(1)
-SVC_Handler
- B SVC_Handler
-
- PUBWEAK PendSV_Handler
- SECTION .text:CODE:REORDER:NOROOT(1)
-PendSV_Handler
- B PendSV_Handler
-
- PUBWEAK SysTick_Handler
- SECTION .text:CODE:REORDER:NOROOT(1)
-SysTick_Handler
- B SysTick_Handler
-
- ; Device specific interrupt handlers
-
- PUBWEAK DMA_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-DMA_IRQHandler
- B DMA_IRQHandler
-
- PUBWEAK GPIO_EVEN_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-GPIO_EVEN_IRQHandler
- B GPIO_EVEN_IRQHandler
-
- PUBWEAK TIMER0_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-TIMER0_IRQHandler
- B TIMER0_IRQHandler
-
- PUBWEAK ACMP0_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-ACMP0_IRQHandler
- B ACMP0_IRQHandler
-
- PUBWEAK ADC0_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-ADC0_IRQHandler
- B ADC0_IRQHandler
-
- PUBWEAK I2C0_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-I2C0_IRQHandler
- B I2C0_IRQHandler
-
- PUBWEAK GPIO_ODD_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-GPIO_ODD_IRQHandler
- B GPIO_ODD_IRQHandler
-
- PUBWEAK TIMER1_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-TIMER1_IRQHandler
- B TIMER1_IRQHandler
-
- PUBWEAK USART1_RX_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-USART1_RX_IRQHandler
- B USART1_RX_IRQHandler
-
- PUBWEAK USART1_TX_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-USART1_TX_IRQHandler
- B USART1_TX_IRQHandler
-
- PUBWEAK LEUART0_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-LEUART0_IRQHandler
- B LEUART0_IRQHandler
-
- PUBWEAK PCNT0_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-PCNT0_IRQHandler
- B PCNT0_IRQHandler
-
- PUBWEAK RTC_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-RTC_IRQHandler
- B RTC_IRQHandler
-
- PUBWEAK CMU_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-CMU_IRQHandler
- B CMU_IRQHandler
-
- PUBWEAK VCMP_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-VCMP_IRQHandler
- B VCMP_IRQHandler
-
- PUBWEAK MSC_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-MSC_IRQHandler
- B MSC_IRQHandler
-
- PUBWEAK AES_IRQHandler
- SECTION .text:CODE:REORDER:NOROOT(1)
-AES_IRQHandler
- B AES_IRQHandler
-
-
- END
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f16.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f16.h
deleted file mode 100644
index d0262fd492..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f16.h
+++ /dev/null
@@ -1,2188 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG108F16
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG108F16_H
-#define EFM32ZG108F16_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16 EFM32ZG108F16
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_Core EFM32ZG108F16 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG108F16_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG108F16_Part EFM32ZG108F16 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG108F16)
-#define EFM32ZG108F16 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG108F16" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG108F16 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00004000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG108F16_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_Peripheral_TypeDefs EFM32ZG108F16 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_dma_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_DMA EFM32ZG108F16 DMA
- * @{
- * @brief EFM32ZG108F16_DMA Register Declaration
- ******************************************************************************/
-typedef struct {
- __IM uint32_t STATUS; /**< DMA Status Registers */
- __OM uint32_t CONFIG; /**< DMA Configuration Register */
- __IOM uint32_t CTRLBASE; /**< Channel Control Data Base Pointer Register */
- __IM uint32_t ALTCTRLBASE; /**< Channel Alternate Control Data Base Pointer Register */
- __IM uint32_t CHWAITSTATUS; /**< Channel Wait on Request Status Register */
- __OM uint32_t CHSWREQ; /**< Channel Software Request Register */
- __IOM uint32_t CHUSEBURSTS; /**< Channel Useburst Set Register */
- __OM uint32_t CHUSEBURSTC; /**< Channel Useburst Clear Register */
- __IOM uint32_t CHREQMASKS; /**< Channel Request Mask Set Register */
- __OM uint32_t CHREQMASKC; /**< Channel Request Mask Clear Register */
- __IOM uint32_t CHENS; /**< Channel Enable Set Register */
- __OM uint32_t CHENC; /**< Channel Enable Clear Register */
- __IOM uint32_t CHALTS; /**< Channel Alternate Set Register */
- __OM uint32_t CHALTC; /**< Channel Alternate Clear Register */
- __IOM uint32_t CHPRIS; /**< Channel Priority Set Register */
- __OM uint32_t CHPRIC; /**< Channel Priority Clear Register */
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t ERRORC; /**< Bus Error Clear Register */
-
- uint32_t RESERVED1[880U]; /**< Reserved for future use **/
- __IM uint32_t CHREQSTATUS; /**< Channel Request Status */
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IM uint32_t CHSREQSTATUS; /**< Channel Single Request Status */
-
- uint32_t RESERVED3[121U]; /**< Reserved for future use **/
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable register */
-
- uint32_t RESERVED4[60U]; /**< Reserved registers */
- DMA_CH_TypeDef CH[4U]; /**< Channel registers */
-} DMA_TypeDef; /** DMA Register Declaration *//** @} */
-
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_CMU EFM32ZG108F16 CMU
- * @{
- * @brief EFM32ZG108F16_CMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< CMU Control Register */
- __IOM uint32_t HFCORECLKDIV; /**< High Frequency Core Clock Division Register */
- __IOM uint32_t HFPERCLKDIV; /**< High Frequency Peripheral Clock Division Register */
- __IOM uint32_t HFRCOCTRL; /**< HFRCO Control Register */
- __IOM uint32_t LFRCOCTRL; /**< LFRCO Control Register */
- __IOM uint32_t AUXHFRCOCTRL; /**< AUXHFRCO Control Register */
- __IOM uint32_t CALCTRL; /**< Calibration Control Register */
- __IOM uint32_t CALCNT; /**< Calibration Counter Register */
- __IOM uint32_t OSCENCMD; /**< Oscillator Enable/Disable Command Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IOM uint32_t LFCLKSEL; /**< Low Frequency Clock Select Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t HFCORECLKEN0; /**< High Frequency Core Clock Enable Register 0 */
- __IOM uint32_t HFPERCLKEN0; /**< High Frequency Peripheral Clock Enable Register 0 */
- uint32_t RESERVED0[2U]; /**< Reserved for future use **/
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IOM uint32_t LFACLKEN0; /**< Low Frequency A Clock Enable Register 0 (Async Reg) */
- uint32_t RESERVED1[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBCLKEN0; /**< Low Frequency B Clock Enable Register 0 (Async Reg) */
-
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFAPRESC0; /**< Low Frequency A Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED3[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBPRESC0; /**< Low Frequency B Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED4[1U]; /**< Reserved for future use **/
- __IOM uint32_t PCNTCTRL; /**< PCNT Control Register */
-
- uint32_t RESERVED5[1U]; /**< Reserved for future use **/
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
-} CMU_TypeDef; /** CMU Register Declaration *//** @} */
-
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_PRS EFM32ZG108F16 PRS
- * @{
- * @brief EFM32ZG108F16_PRS Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t SWPULSE; /**< Software Pulse Register */
- __IOM uint32_t SWLEVEL; /**< Software Level Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved registers */
- PRS_CH_TypeDef CH[4U]; /**< Channel registers */
-} PRS_TypeDef; /** PRS Register Declaration *//** @} */
-
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG108F16_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_Peripheral_Base EFM32ZG108F16 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG108F16_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_Peripheral_Declaration EFM32ZG108F16 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG108F16_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_BitFields EFM32ZG108F16 Bit Fields
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @addtogroup EFM32ZG108F16_PRS_Signals
- * @{
- * @brief PRS Signal names
- ******************************************************************************/
-#define PRS_VCMP_OUT ((1 << 16) + 0) /**< PRS Voltage comparator output */
-#define PRS_ACMP0_OUT ((2 << 16) + 0) /**< PRS Analog comparator output */
-#define PRS_USART1_IRTX ((17 << 16) + 0) /**< PRS USART 1 IRDA out */
-#define PRS_USART1_TXC ((17 << 16) + 1) /**< PRS USART 1 TX complete */
-#define PRS_USART1_RXDATAV ((17 << 16) + 2) /**< PRS USART 1 RX Data Valid */
-#define PRS_TIMER0_UF ((28 << 16) + 0) /**< PRS Timer 0 Underflow */
-#define PRS_TIMER0_OF ((28 << 16) + 1) /**< PRS Timer 0 Overflow */
-#define PRS_TIMER0_CC0 ((28 << 16) + 2) /**< PRS Timer 0 Compare/Capture 0 */
-#define PRS_TIMER0_CC1 ((28 << 16) + 3) /**< PRS Timer 0 Compare/Capture 1 */
-#define PRS_TIMER0_CC2 ((28 << 16) + 4) /**< PRS Timer 0 Compare/Capture 2 */
-#define PRS_TIMER1_UF ((29 << 16) + 0) /**< PRS Timer 1 Underflow */
-#define PRS_TIMER1_OF ((29 << 16) + 1) /**< PRS Timer 1 Overflow */
-#define PRS_TIMER1_CC0 ((29 << 16) + 2) /**< PRS Timer 1 Compare/Capture 0 */
-#define PRS_TIMER1_CC1 ((29 << 16) + 3) /**< PRS Timer 1 Compare/Capture 1 */
-#define PRS_TIMER1_CC2 ((29 << 16) + 4) /**< PRS Timer 1 Compare/Capture 2 */
-#define PRS_RTC_OF ((40 << 16) + 0) /**< PRS RTC Overflow */
-#define PRS_RTC_COMP0 ((40 << 16) + 1) /**< PRS RTC Compare 0 */
-#define PRS_RTC_COMP1 ((40 << 16) + 2) /**< PRS RTC Compare 1 */
-#define PRS_GPIO_PIN0 ((48 << 16) + 0) /**< PRS GPIO pin 0 */
-#define PRS_GPIO_PIN1 ((48 << 16) + 1) /**< PRS GPIO pin 1 */
-#define PRS_GPIO_PIN2 ((48 << 16) + 2) /**< PRS GPIO pin 2 */
-#define PRS_GPIO_PIN3 ((48 << 16) + 3) /**< PRS GPIO pin 3 */
-#define PRS_GPIO_PIN4 ((48 << 16) + 4) /**< PRS GPIO pin 4 */
-#define PRS_GPIO_PIN5 ((48 << 16) + 5) /**< PRS GPIO pin 5 */
-#define PRS_GPIO_PIN6 ((48 << 16) + 6) /**< PRS GPIO pin 6 */
-#define PRS_GPIO_PIN7 ((48 << 16) + 7) /**< PRS GPIO pin 7 */
-#define PRS_GPIO_PIN8 ((49 << 16) + 0) /**< PRS GPIO pin 8 */
-#define PRS_GPIO_PIN9 ((49 << 16) + 1) /**< PRS GPIO pin 9 */
-#define PRS_GPIO_PIN10 ((49 << 16) + 2) /**< PRS GPIO pin 10 */
-#define PRS_GPIO_PIN11 ((49 << 16) + 3) /**< PRS GPIO pin 11 */
-#define PRS_GPIO_PIN12 ((49 << 16) + 4) /**< PRS GPIO pin 12 */
-#define PRS_GPIO_PIN13 ((49 << 16) + 5) /**< PRS GPIO pin 13 */
-#define PRS_GPIO_PIN14 ((49 << 16) + 6) /**< PRS GPIO pin 14 */
-#define PRS_GPIO_PIN15 ((49 << 16) + 7) /**< PRS GPIO pin 15 */
-#define PRS_PCNT0_TCC ((54 << 16) + 0) /**< PRS Triggered compare match */
-
-/** @} End of group EFM32ZG108F16_PRS */
-
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_DMA_BitFields EFM32ZG108F16_DMA Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for DMA STATUS */
-#define _DMA_STATUS_RESETVALUE 0x10030000UL /**< Default value for DMA_STATUS */
-#define _DMA_STATUS_MASK 0x001F00F1UL /**< Mask for DMA_STATUS */
-#define DMA_STATUS_EN (0x1UL << 0) /**< DMA Enable Status */
-#define _DMA_STATUS_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_STATUS_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_STATUS_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_EN_DEFAULT (_DMA_STATUS_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_SHIFT 4 /**< Shift value for DMA_STATE */
-#define _DMA_STATUS_STATE_MASK 0xF0UL /**< Bit mask for DMA_STATE */
-#define _DMA_STATUS_STATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_IDLE 0x00000000UL /**< Mode IDLE for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDCHCTRLDATA 0x00000001UL /**< Mode RDCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCENDPTR 0x00000002UL /**< Mode RDSRCENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDDSTENDPTR 0x00000003UL /**< Mode RDDSTENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCDATA 0x00000004UL /**< Mode RDSRCDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRDSTDATA 0x00000005UL /**< Mode WRDSTDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WAITREQCLR 0x00000006UL /**< Mode WAITREQCLR for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRCHCTRLDATA 0x00000007UL /**< Mode WRCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_STALLED 0x00000008UL /**< Mode STALLED for DMA_STATUS */
-#define _DMA_STATUS_STATE_DONE 0x00000009UL /**< Mode DONE for DMA_STATUS */
-#define _DMA_STATUS_STATE_PERSCATTRANS 0x0000000AUL /**< Mode PERSCATTRANS for DMA_STATUS */
-#define DMA_STATUS_STATE_DEFAULT (_DMA_STATUS_STATE_DEFAULT << 4) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_STATE_IDLE (_DMA_STATUS_STATE_IDLE << 4) /**< Shifted mode IDLE for DMA_STATUS */
-#define DMA_STATUS_STATE_RDCHCTRLDATA (_DMA_STATUS_STATE_RDCHCTRLDATA << 4) /**< Shifted mode RDCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCENDPTR (_DMA_STATUS_STATE_RDSRCENDPTR << 4) /**< Shifted mode RDSRCENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDDSTENDPTR (_DMA_STATUS_STATE_RDDSTENDPTR << 4) /**< Shifted mode RDDSTENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCDATA (_DMA_STATUS_STATE_RDSRCDATA << 4) /**< Shifted mode RDSRCDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WRDSTDATA (_DMA_STATUS_STATE_WRDSTDATA << 4) /**< Shifted mode WRDSTDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WAITREQCLR (_DMA_STATUS_STATE_WAITREQCLR << 4) /**< Shifted mode WAITREQCLR for DMA_STATUS */
-#define DMA_STATUS_STATE_WRCHCTRLDATA (_DMA_STATUS_STATE_WRCHCTRLDATA << 4) /**< Shifted mode WRCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_STALLED (_DMA_STATUS_STATE_STALLED << 4) /**< Shifted mode STALLED for DMA_STATUS */
-#define DMA_STATUS_STATE_DONE (_DMA_STATUS_STATE_DONE << 4) /**< Shifted mode DONE for DMA_STATUS */
-#define DMA_STATUS_STATE_PERSCATTRANS (_DMA_STATUS_STATE_PERSCATTRANS << 4) /**< Shifted mode PERSCATTRANS for DMA_STATUS */
-#define _DMA_STATUS_CHNUM_SHIFT 16 /**< Shift value for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_MASK 0x1F0000UL /**< Bit mask for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_DEFAULT 0x00000003UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_CHNUM_DEFAULT (_DMA_STATUS_CHNUM_DEFAULT << 16) /**< Shifted mode DEFAULT for DMA_STATUS */
-
-/* Bit fields for DMA CONFIG */
-#define _DMA_CONFIG_RESETVALUE 0x00000000UL /**< Default value for DMA_CONFIG */
-#define _DMA_CONFIG_MASK 0x00000021UL /**< Mask for DMA_CONFIG */
-#define DMA_CONFIG_EN (0x1UL << 0) /**< Enable DMA */
-#define _DMA_CONFIG_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_CONFIG_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_CONFIG_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_EN_DEFAULT (_DMA_CONFIG_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT (0x1UL << 5) /**< Channel Protection Control */
-#define _DMA_CONFIG_CHPROT_SHIFT 5 /**< Shift value for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_MASK 0x20UL /**< Bit mask for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT_DEFAULT (_DMA_CONFIG_CHPROT_DEFAULT << 5) /**< Shifted mode DEFAULT for DMA_CONFIG */
-
-/* Bit fields for DMA CTRLBASE */
-#define _DMA_CTRLBASE_RESETVALUE 0x00000000UL /**< Default value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_SHIFT 0 /**< Shift value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CTRLBASE */
-#define DMA_CTRLBASE_CTRLBASE_DEFAULT (_DMA_CTRLBASE_CTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CTRLBASE */
-
-/* Bit fields for DMA ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_RESETVALUE 0x00000040UL /**< Default value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_SHIFT 0 /**< Shift value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT 0x00000040UL /**< Mode DEFAULT for DMA_ALTCTRLBASE */
-#define DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT (_DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ALTCTRLBASE */
-
-/* Bit fields for DMA CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_RESETVALUE 0x0000000FUL /**< Default value for DMA_CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS (0x1UL << 0) /**< Channel 0 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_SHIFT 0 /**< Shift value for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS (0x1UL << 1) /**< Channel 1 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_SHIFT 1 /**< Shift value for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS (0x1UL << 2) /**< Channel 2 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_SHIFT 2 /**< Shift value for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS (0x1UL << 3) /**< Channel 3 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_SHIFT 3 /**< Shift value for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-
-/* Bit fields for DMA CHSWREQ */
-#define _DMA_CHSWREQ_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSWREQ */
-#define _DMA_CHSWREQ_MASK 0x0000000FUL /**< Mask for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ (0x1UL << 0) /**< Channel 0 Software Request */
-#define _DMA_CHSWREQ_CH0SWREQ_SHIFT 0 /**< Shift value for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_MASK 0x1UL /**< Bit mask for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ_DEFAULT (_DMA_CHSWREQ_CH0SWREQ_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ (0x1UL << 1) /**< Channel 1 Software Request */
-#define _DMA_CHSWREQ_CH1SWREQ_SHIFT 1 /**< Shift value for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_MASK 0x2UL /**< Bit mask for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ_DEFAULT (_DMA_CHSWREQ_CH1SWREQ_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ (0x1UL << 2) /**< Channel 2 Software Request */
-#define _DMA_CHSWREQ_CH2SWREQ_SHIFT 2 /**< Shift value for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_MASK 0x4UL /**< Bit mask for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ_DEFAULT (_DMA_CHSWREQ_CH2SWREQ_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ (0x1UL << 3) /**< Channel 3 Software Request */
-#define _DMA_CHSWREQ_CH3SWREQ_SHIFT 3 /**< Shift value for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_MASK 0x8UL /**< Bit mask for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ_DEFAULT (_DMA_CHSWREQ_CH3SWREQ_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-
-/* Bit fields for DMA CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS (0x1UL << 0) /**< Channel 0 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST 0x00000000UL /**< Mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY 0x00000001UL /**< Mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST (_DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST << 0) /**< Shifted mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY (_DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY << 0) /**< Shifted mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS (0x1UL << 1) /**< Channel 1 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS (0x1UL << 2) /**< Channel 2 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS (0x1UL << 3) /**< Channel 3 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-
-/* Bit fields for DMA CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC (0x1UL << 0) /**< Channel 0 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC (0x1UL << 1) /**< Channel 1 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC (0x1UL << 2) /**< Channel 2 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC (0x1UL << 3) /**< Channel 3 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-
-/* Bit fields for DMA CHREQMASKS */
-#define _DMA_CHREQMASKS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKS */
-#define _DMA_CHREQMASKS_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS (0x1UL << 0) /**< Channel 0 Request Mask Set */
-#define _DMA_CHREQMASKS_CH0REQMASKS_SHIFT 0 /**< Shift value for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH0REQMASKS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS (0x1UL << 1) /**< Channel 1 Request Mask Set */
-#define _DMA_CHREQMASKS_CH1REQMASKS_SHIFT 1 /**< Shift value for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH1REQMASKS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS (0x1UL << 2) /**< Channel 2 Request Mask Set */
-#define _DMA_CHREQMASKS_CH2REQMASKS_SHIFT 2 /**< Shift value for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH2REQMASKS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS (0x1UL << 3) /**< Channel 3 Request Mask Set */
-#define _DMA_CHREQMASKS_CH3REQMASKS_SHIFT 3 /**< Shift value for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH3REQMASKS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-
-/* Bit fields for DMA CHREQMASKC */
-#define _DMA_CHREQMASKC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKC */
-#define _DMA_CHREQMASKC_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC (0x1UL << 0) /**< Channel 0 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH0REQMASKC_SHIFT 0 /**< Shift value for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH0REQMASKC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC (0x1UL << 1) /**< Channel 1 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH1REQMASKC_SHIFT 1 /**< Shift value for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH1REQMASKC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC (0x1UL << 2) /**< Channel 2 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH2REQMASKC_SHIFT 2 /**< Shift value for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH2REQMASKC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC (0x1UL << 3) /**< Channel 3 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH3REQMASKC_SHIFT 3 /**< Shift value for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH3REQMASKC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-
-/* Bit fields for DMA CHENS */
-#define _DMA_CHENS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENS */
-#define _DMA_CHENS_MASK 0x0000000FUL /**< Mask for DMA_CHENS */
-#define DMA_CHENS_CH0ENS (0x1UL << 0) /**< Channel 0 Enable Set */
-#define _DMA_CHENS_CH0ENS_SHIFT 0 /**< Shift value for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_MASK 0x1UL /**< Bit mask for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH0ENS_DEFAULT (_DMA_CHENS_CH0ENS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS (0x1UL << 1) /**< Channel 1 Enable Set */
-#define _DMA_CHENS_CH1ENS_SHIFT 1 /**< Shift value for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_MASK 0x2UL /**< Bit mask for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS_DEFAULT (_DMA_CHENS_CH1ENS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS (0x1UL << 2) /**< Channel 2 Enable Set */
-#define _DMA_CHENS_CH2ENS_SHIFT 2 /**< Shift value for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_MASK 0x4UL /**< Bit mask for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS_DEFAULT (_DMA_CHENS_CH2ENS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS (0x1UL << 3) /**< Channel 3 Enable Set */
-#define _DMA_CHENS_CH3ENS_SHIFT 3 /**< Shift value for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_MASK 0x8UL /**< Bit mask for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS_DEFAULT (_DMA_CHENS_CH3ENS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENS */
-
-/* Bit fields for DMA CHENC */
-#define _DMA_CHENC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENC */
-#define _DMA_CHENC_MASK 0x0000000FUL /**< Mask for DMA_CHENC */
-#define DMA_CHENC_CH0ENC (0x1UL << 0) /**< Channel 0 Enable Clear */
-#define _DMA_CHENC_CH0ENC_SHIFT 0 /**< Shift value for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_MASK 0x1UL /**< Bit mask for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH0ENC_DEFAULT (_DMA_CHENC_CH0ENC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC (0x1UL << 1) /**< Channel 1 Enable Clear */
-#define _DMA_CHENC_CH1ENC_SHIFT 1 /**< Shift value for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_MASK 0x2UL /**< Bit mask for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC_DEFAULT (_DMA_CHENC_CH1ENC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC (0x1UL << 2) /**< Channel 2 Enable Clear */
-#define _DMA_CHENC_CH2ENC_SHIFT 2 /**< Shift value for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_MASK 0x4UL /**< Bit mask for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC_DEFAULT (_DMA_CHENC_CH2ENC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC (0x1UL << 3) /**< Channel 3 Enable Clear */
-#define _DMA_CHENC_CH3ENC_SHIFT 3 /**< Shift value for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_MASK 0x8UL /**< Bit mask for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC_DEFAULT (_DMA_CHENC_CH3ENC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENC */
-
-/* Bit fields for DMA CHALTS */
-#define _DMA_CHALTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTS */
-#define _DMA_CHALTS_MASK 0x0000000FUL /**< Mask for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS (0x1UL << 0) /**< Channel 0 Alternate Structure Set */
-#define _DMA_CHALTS_CH0ALTS_SHIFT 0 /**< Shift value for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_MASK 0x1UL /**< Bit mask for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS_DEFAULT (_DMA_CHALTS_CH0ALTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS (0x1UL << 1) /**< Channel 1 Alternate Structure Set */
-#define _DMA_CHALTS_CH1ALTS_SHIFT 1 /**< Shift value for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_MASK 0x2UL /**< Bit mask for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS_DEFAULT (_DMA_CHALTS_CH1ALTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS (0x1UL << 2) /**< Channel 2 Alternate Structure Set */
-#define _DMA_CHALTS_CH2ALTS_SHIFT 2 /**< Shift value for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_MASK 0x4UL /**< Bit mask for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS_DEFAULT (_DMA_CHALTS_CH2ALTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS (0x1UL << 3) /**< Channel 3 Alternate Structure Set */
-#define _DMA_CHALTS_CH3ALTS_SHIFT 3 /**< Shift value for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_MASK 0x8UL /**< Bit mask for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS_DEFAULT (_DMA_CHALTS_CH3ALTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTS */
-
-/* Bit fields for DMA CHALTC */
-#define _DMA_CHALTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTC */
-#define _DMA_CHALTC_MASK 0x0000000FUL /**< Mask for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC (0x1UL << 0) /**< Channel 0 Alternate Clear */
-#define _DMA_CHALTC_CH0ALTC_SHIFT 0 /**< Shift value for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_MASK 0x1UL /**< Bit mask for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC_DEFAULT (_DMA_CHALTC_CH0ALTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC (0x1UL << 1) /**< Channel 1 Alternate Clear */
-#define _DMA_CHALTC_CH1ALTC_SHIFT 1 /**< Shift value for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_MASK 0x2UL /**< Bit mask for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC_DEFAULT (_DMA_CHALTC_CH1ALTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC (0x1UL << 2) /**< Channel 2 Alternate Clear */
-#define _DMA_CHALTC_CH2ALTC_SHIFT 2 /**< Shift value for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_MASK 0x4UL /**< Bit mask for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC_DEFAULT (_DMA_CHALTC_CH2ALTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC (0x1UL << 3) /**< Channel 3 Alternate Clear */
-#define _DMA_CHALTC_CH3ALTC_SHIFT 3 /**< Shift value for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_MASK 0x8UL /**< Bit mask for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC_DEFAULT (_DMA_CHALTC_CH3ALTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTC */
-
-/* Bit fields for DMA CHPRIS */
-#define _DMA_CHPRIS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIS */
-#define _DMA_CHPRIS_MASK 0x0000000FUL /**< Mask for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS (0x1UL << 0) /**< Channel 0 High Priority Set */
-#define _DMA_CHPRIS_CH0PRIS_SHIFT 0 /**< Shift value for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_MASK 0x1UL /**< Bit mask for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS_DEFAULT (_DMA_CHPRIS_CH0PRIS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS (0x1UL << 1) /**< Channel 1 High Priority Set */
-#define _DMA_CHPRIS_CH1PRIS_SHIFT 1 /**< Shift value for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_MASK 0x2UL /**< Bit mask for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS_DEFAULT (_DMA_CHPRIS_CH1PRIS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS (0x1UL << 2) /**< Channel 2 High Priority Set */
-#define _DMA_CHPRIS_CH2PRIS_SHIFT 2 /**< Shift value for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_MASK 0x4UL /**< Bit mask for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS_DEFAULT (_DMA_CHPRIS_CH2PRIS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS (0x1UL << 3) /**< Channel 3 High Priority Set */
-#define _DMA_CHPRIS_CH3PRIS_SHIFT 3 /**< Shift value for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_MASK 0x8UL /**< Bit mask for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS_DEFAULT (_DMA_CHPRIS_CH3PRIS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-
-/* Bit fields for DMA CHPRIC */
-#define _DMA_CHPRIC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIC */
-#define _DMA_CHPRIC_MASK 0x0000000FUL /**< Mask for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC (0x1UL << 0) /**< Channel 0 High Priority Clear */
-#define _DMA_CHPRIC_CH0PRIC_SHIFT 0 /**< Shift value for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_MASK 0x1UL /**< Bit mask for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC_DEFAULT (_DMA_CHPRIC_CH0PRIC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC (0x1UL << 1) /**< Channel 1 High Priority Clear */
-#define _DMA_CHPRIC_CH1PRIC_SHIFT 1 /**< Shift value for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_MASK 0x2UL /**< Bit mask for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC_DEFAULT (_DMA_CHPRIC_CH1PRIC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC (0x1UL << 2) /**< Channel 2 High Priority Clear */
-#define _DMA_CHPRIC_CH2PRIC_SHIFT 2 /**< Shift value for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_MASK 0x4UL /**< Bit mask for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC_DEFAULT (_DMA_CHPRIC_CH2PRIC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC (0x1UL << 3) /**< Channel 3 High Priority Clear */
-#define _DMA_CHPRIC_CH3PRIC_SHIFT 3 /**< Shift value for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_MASK 0x8UL /**< Bit mask for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC_DEFAULT (_DMA_CHPRIC_CH3PRIC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-
-/* Bit fields for DMA ERRORC */
-#define _DMA_ERRORC_RESETVALUE 0x00000000UL /**< Default value for DMA_ERRORC */
-#define _DMA_ERRORC_MASK 0x00000001UL /**< Mask for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC (0x1UL << 0) /**< Bus Error Clear */
-#define _DMA_ERRORC_ERRORC_SHIFT 0 /**< Shift value for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_MASK 0x1UL /**< Bit mask for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC_DEFAULT (_DMA_ERRORC_ERRORC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ERRORC */
-
-/* Bit fields for DMA CHREQSTATUS */
-#define _DMA_CHREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQSTATUS */
-#define _DMA_CHREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS (0x1UL << 0) /**< Channel 0 Request Status */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS (0x1UL << 1) /**< Channel 1 Request Status */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS (0x1UL << 2) /**< Channel 2 Request Status */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS (0x1UL << 3) /**< Channel 3 Request Status */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-
-/* Bit fields for DMA CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS (0x1UL << 0) /**< Channel 0 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS (0x1UL << 1) /**< Channel 1 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS (0x1UL << 2) /**< Channel 2 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS (0x1UL << 3) /**< Channel 3 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-
-/* Bit fields for DMA IF */
-#define _DMA_IF_RESETVALUE 0x00000000UL /**< Default value for DMA_IF */
-#define _DMA_IF_MASK 0x8000000FUL /**< Mask for DMA_IF */
-#define DMA_IF_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag */
-#define _DMA_IF_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH0DONE_DEFAULT (_DMA_IF_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag */
-#define _DMA_IF_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE_DEFAULT (_DMA_IF_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag */
-#define _DMA_IF_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE_DEFAULT (_DMA_IF_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag */
-#define _DMA_IF_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE_DEFAULT (_DMA_IF_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag */
-#define _DMA_IF_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IF_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IF_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR_DEFAULT (_DMA_IF_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IF */
-
-/* Bit fields for DMA IFS */
-#define _DMA_IFS_RESETVALUE 0x00000000UL /**< Default value for DMA_IFS */
-#define _DMA_IFS_MASK 0x8000000FUL /**< Mask for DMA_IFS */
-#define DMA_IFS_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH0DONE_DEFAULT (_DMA_IFS_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE_DEFAULT (_DMA_IFS_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE_DEFAULT (_DMA_IFS_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE_DEFAULT (_DMA_IFS_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Set */
-#define _DMA_IFS_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFS_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFS_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR_DEFAULT (_DMA_IFS_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFS */
-
-/* Bit fields for DMA IFC */
-#define _DMA_IFC_RESETVALUE 0x00000000UL /**< Default value for DMA_IFC */
-#define _DMA_IFC_MASK 0x8000000FUL /**< Mask for DMA_IFC */
-#define DMA_IFC_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH0DONE_DEFAULT (_DMA_IFC_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE_DEFAULT (_DMA_IFC_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE_DEFAULT (_DMA_IFC_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE_DEFAULT (_DMA_IFC_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Clear */
-#define _DMA_IFC_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFC_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFC_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR_DEFAULT (_DMA_IFC_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFC */
-
-/* Bit fields for DMA IEN */
-#define _DMA_IEN_RESETVALUE 0x00000000UL /**< Default value for DMA_IEN */
-#define _DMA_IEN_MASK 0x8000000FUL /**< Mask for DMA_IEN */
-#define DMA_IEN_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Enable */
-#define _DMA_IEN_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH0DONE_DEFAULT (_DMA_IEN_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Enable */
-#define _DMA_IEN_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE_DEFAULT (_DMA_IEN_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Enable */
-#define _DMA_IEN_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE_DEFAULT (_DMA_IEN_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Enable */
-#define _DMA_IEN_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE_DEFAULT (_DMA_IEN_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Enable */
-#define _DMA_IEN_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IEN_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IEN_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR_DEFAULT (_DMA_IEN_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IEN */
-
-/* Bit fields for DMA CH_CTRL */
-#define _DMA_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_MASK 0x003F000FUL /**< Mask for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_MASK 0xFUL /**< Bit mask for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000000UL /**< Mode USART1RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV 0x00000000UL /**< Mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0RXDATAV 0x00000000UL /**< Mode I2C0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0UFOF 0x00000000UL /**< Mode TIMER0UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1UFOF 0x00000000UL /**< Mode TIMER1UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_MSCWDATA 0x00000000UL /**< Mode MSCWDATA for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBL 0x00000001UL /**< Mode USART1TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXBL 0x00000001UL /**< Mode LEUART0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0TXBL 0x00000001UL /**< Mode I2C0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC0 0x00000001UL /**< Mode TIMER0CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC0 0x00000001UL /**< Mode TIMER1CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXEMPTY 0x00000002UL /**< Mode USART1TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY 0x00000002UL /**< Mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC1 0x00000002UL /**< Mode TIMER0CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC1 0x00000002UL /**< Mode TIMER1CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT 0x00000003UL /**< Mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC2 0x00000003UL /**< Mode TIMER0CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC2 0x00000003UL /**< Mode TIMER1CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT 0x00000004UL /**< Mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAV (_DMA_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV (_DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV << 0) /**< Shifted mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0RXDATAV (_DMA_CH_CTRL_SIGSEL_I2C0RXDATAV << 0) /**< Shifted mode I2C0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0UFOF (_DMA_CH_CTRL_SIGSEL_TIMER0UFOF << 0) /**< Shifted mode TIMER0UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1UFOF (_DMA_CH_CTRL_SIGSEL_TIMER1UFOF << 0) /**< Shifted mode TIMER1UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_MSCWDATA (_DMA_CH_CTRL_SIGSEL_MSCWDATA << 0) /**< Shifted mode MSCWDATA for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBL (_DMA_CH_CTRL_SIGSEL_USART1TXBL << 0) /**< Shifted mode USART1TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXBL (_DMA_CH_CTRL_SIGSEL_LEUART0TXBL << 0) /**< Shifted mode LEUART0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0TXBL (_DMA_CH_CTRL_SIGSEL_I2C0TXBL << 0) /**< Shifted mode I2C0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC0 (_DMA_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC0 (_DMA_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXEMPTY (_DMA_CH_CTRL_SIGSEL_USART1TXEMPTY << 0) /**< Shifted mode USART1TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY (_DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY << 0) /**< Shifted mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC1 (_DMA_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC1 (_DMA_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT (_DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT << 0) /**< Shifted mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC2 (_DMA_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC2 (_DMA_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT (_DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT << 0) /**< Shifted mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_USART1 0x0000000DUL /**< Mode USART1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_LEUART0 0x00000010UL /**< Mode LEUART0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_I2C0 0x00000014UL /**< Mode I2C0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER0 0x00000018UL /**< Mode TIMER0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER1 0x00000019UL /**< Mode TIMER1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_MSC 0x00000030UL /**< Mode MSC for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_NONE (_DMA_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_USART1 (_DMA_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_LEUART0 (_DMA_CH_CTRL_SOURCESEL_LEUART0 << 16) /**< Shifted mode LEUART0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_I2C0 (_DMA_CH_CTRL_SOURCESEL_I2C0 << 16) /**< Shifted mode I2C0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER0 (_DMA_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER1 (_DMA_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_MSC (_DMA_CH_CTRL_SOURCESEL_MSC << 16) /**< Shifted mode MSC for DMA_CH_CTRL */
-
-/** @} End of group EFM32ZG108F16_DMA */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_CMU_BitFields EFM32ZG108F16_CMU Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for CMU CTRL */
-#define _CMU_CTRL_RESETVALUE 0x000C262CUL /**< Default value for CMU_CTRL */
-#define _CMU_CTRL_MASK 0x07FE3EEFUL /**< Mask for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_SHIFT 0 /**< Shift value for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_MASK 0x3UL /**< Bit mask for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DEFAULT (_CMU_CTRL_HFXOMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_XTAL (_CMU_CTRL_HFXOMODE_XTAL << 0) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_BUFEXTCLK (_CMU_CTRL_HFXOMODE_BUFEXTCLK << 0) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DIGEXTCLK (_CMU_CTRL_HFXOMODE_DIGEXTCLK << 0) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_SHIFT 2 /**< Shift value for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_MASK 0xCUL /**< Bit mask for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_50PCENT 0x00000000UL /**< Mode 50PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_70PCENT 0x00000001UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_80PCENT 0x00000002UL /**< Mode 80PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_100PCENT 0x00000003UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_50PCENT (_CMU_CTRL_HFXOBOOST_50PCENT << 2) /**< Shifted mode 50PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_70PCENT (_CMU_CTRL_HFXOBOOST_70PCENT << 2) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_80PCENT (_CMU_CTRL_HFXOBOOST_80PCENT << 2) /**< Shifted mode 80PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_DEFAULT (_CMU_CTRL_HFXOBOOST_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_100PCENT (_CMU_CTRL_HFXOBOOST_100PCENT << 2) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBUFCUR_SHIFT 5 /**< Shift value for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_MASK 0x60UL /**< Bit mask for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBUFCUR_DEFAULT (_CMU_CTRL_HFXOBUFCUR_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN (0x1UL << 7) /**< HFXO Glitch Detector Enable */
-#define _CMU_CTRL_HFXOGLITCHDETEN_SHIFT 7 /**< Shift value for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_MASK 0x80UL /**< Bit mask for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN_DEFAULT (_CMU_CTRL_HFXOGLITCHDETEN_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_SHIFT 9 /**< Shift value for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_MASK 0x600UL /**< Bit mask for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_256CYCLES 0x00000001UL /**< Mode 256CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_1KCYCLES 0x00000002UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_16KCYCLES 0x00000003UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_8CYCLES (_CMU_CTRL_HFXOTIMEOUT_8CYCLES << 9) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_256CYCLES (_CMU_CTRL_HFXOTIMEOUT_256CYCLES << 9) /**< Shifted mode 256CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_1KCYCLES (_CMU_CTRL_HFXOTIMEOUT_1KCYCLES << 9) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_DEFAULT (_CMU_CTRL_HFXOTIMEOUT_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_16KCYCLES (_CMU_CTRL_HFXOTIMEOUT_16KCYCLES << 9) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_SHIFT 11 /**< Shift value for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_MASK 0x1800UL /**< Bit mask for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DEFAULT (_CMU_CTRL_LFXOMODE_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_XTAL (_CMU_CTRL_LFXOMODE_XTAL << 11) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_BUFEXTCLK (_CMU_CTRL_LFXOMODE_BUFEXTCLK << 11) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DIGEXTCLK (_CMU_CTRL_LFXOMODE_DIGEXTCLK << 11) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST (0x1UL << 13) /**< LFXO Start-up Boost Current */
-#define _CMU_CTRL_LFXOBOOST_SHIFT 13 /**< Shift value for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_MASK 0x2000UL /**< Bit mask for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_70PCENT 0x00000000UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_100PCENT 0x00000001UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_70PCENT (_CMU_CTRL_LFXOBOOST_70PCENT << 13) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_DEFAULT (_CMU_CTRL_LFXOBOOST_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_100PCENT (_CMU_CTRL_LFXOBOOST_100PCENT << 13) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR (0x1UL << 17) /**< LFXO Boost Buffer Current */
-#define _CMU_CTRL_LFXOBUFCUR_SHIFT 17 /**< Shift value for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_MASK 0x20000UL /**< Bit mask for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR_DEFAULT (_CMU_CTRL_LFXOBUFCUR_DEFAULT << 17) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_SHIFT 18 /**< Shift value for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_MASK 0xC0000UL /**< Bit mask for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_1KCYCLES 0x00000001UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_16KCYCLES 0x00000002UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_32KCYCLES 0x00000003UL /**< Mode 32KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_8CYCLES (_CMU_CTRL_LFXOTIMEOUT_8CYCLES << 18) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_1KCYCLES (_CMU_CTRL_LFXOTIMEOUT_1KCYCLES << 18) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_16KCYCLES (_CMU_CTRL_LFXOTIMEOUT_16KCYCLES << 18) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_DEFAULT (_CMU_CTRL_LFXOTIMEOUT_DEFAULT << 18) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_32KCYCLES (_CMU_CTRL_LFXOTIMEOUT_32KCYCLES << 18) /**< Shifted mode 32KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_SHIFT 20 /**< Shift value for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_MASK 0x700000UL /**< Bit mask for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFRCO 0x00000000UL /**< Mode HFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFXO 0x00000001UL /**< Mode HFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK2 0x00000002UL /**< Mode HFCLK2 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK4 0x00000003UL /**< Mode HFCLK4 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK8 0x00000004UL /**< Mode HFCLK8 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK16 0x00000005UL /**< Mode HFCLK16 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_ULFRCO 0x00000006UL /**< Mode ULFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_AUXHFRCO 0x00000007UL /**< Mode AUXHFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_DEFAULT (_CMU_CTRL_CLKOUTSEL0_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFRCO (_CMU_CTRL_CLKOUTSEL0_HFRCO << 20) /**< Shifted mode HFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFXO (_CMU_CTRL_CLKOUTSEL0_HFXO << 20) /**< Shifted mode HFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK2 (_CMU_CTRL_CLKOUTSEL0_HFCLK2 << 20) /**< Shifted mode HFCLK2 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK4 (_CMU_CTRL_CLKOUTSEL0_HFCLK4 << 20) /**< Shifted mode HFCLK4 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK8 (_CMU_CTRL_CLKOUTSEL0_HFCLK8 << 20) /**< Shifted mode HFCLK8 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK16 (_CMU_CTRL_CLKOUTSEL0_HFCLK16 << 20) /**< Shifted mode HFCLK16 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_ULFRCO (_CMU_CTRL_CLKOUTSEL0_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_AUXHFRCO (_CMU_CTRL_CLKOUTSEL0_AUXHFRCO << 20) /**< Shifted mode AUXHFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_SHIFT 23 /**< Shift value for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_MASK 0x7800000UL /**< Bit mask for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCO 0x00000000UL /**< Mode LFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXO 0x00000001UL /**< Mode LFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFCLK 0x00000002UL /**< Mode HFCLK for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXOQ 0x00000003UL /**< Mode LFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFXOQ 0x00000004UL /**< Mode HFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCOQ 0x00000005UL /**< Mode LFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFRCOQ 0x00000006UL /**< Mode HFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ 0x00000007UL /**< Mode AUXHFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_DEFAULT (_CMU_CTRL_CLKOUTSEL1_DEFAULT << 23) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCO (_CMU_CTRL_CLKOUTSEL1_LFRCO << 23) /**< Shifted mode LFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXO (_CMU_CTRL_CLKOUTSEL1_LFXO << 23) /**< Shifted mode LFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFCLK (_CMU_CTRL_CLKOUTSEL1_HFCLK << 23) /**< Shifted mode HFCLK for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXOQ (_CMU_CTRL_CLKOUTSEL1_LFXOQ << 23) /**< Shifted mode LFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFXOQ (_CMU_CTRL_CLKOUTSEL1_HFXOQ << 23) /**< Shifted mode HFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCOQ (_CMU_CTRL_CLKOUTSEL1_LFRCOQ << 23) /**< Shifted mode LFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFRCOQ (_CMU_CTRL_CLKOUTSEL1_HFRCOQ << 23) /**< Shifted mode HFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ (_CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ << 23) /**< Shifted mode AUXHFRCOQ for CMU_CTRL */
-
-/* Bit fields for CMU HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_SHIFT 0 /**< Shift value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV (0x1UL << 8) /**< Additional Division Factor For HFCORECLKLE */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_SHIFT 8 /**< Shift value for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_MASK 0x100UL /**< Bit mask for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 0x00000000UL /**< Mode DIV2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 0x00000001UL /**< Mode DIV4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 << 8) /**< Shifted mode DIV2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 << 8) /**< Shifted mode DIV4 for CMU_HFCORECLKDIV */
-
-/* Bit fields for CMU HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_RESETVALUE 0x00000100UL /**< Default value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_SHIFT 0 /**< Shift value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN (0x1UL << 8) /**< HFPERCLK Enable */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_SHIFT 8 /**< Shift value for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_MASK 0x100UL /**< Bit mask for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-
-/* Bit fields for CMU HFRCOCTRL */
-#define _CMU_HFRCOCTRL_RESETVALUE 0x00000380UL /**< Default value for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_MASK 0x0001F7FFUL /**< Mask for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_TUNING_DEFAULT (_CMU_HFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_1MHZ 0x00000000UL /**< Mode 1MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_7MHZ 0x00000001UL /**< Mode 7MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_11MHZ 0x00000002UL /**< Mode 11MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_14MHZ 0x00000003UL /**< Mode 14MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_21MHZ 0x00000004UL /**< Mode 21MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_1MHZ (_CMU_HFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_7MHZ (_CMU_HFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_11MHZ (_CMU_HFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_DEFAULT (_CMU_HFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_14MHZ (_CMU_HFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_21MHZ (_CMU_HFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_SUDELAY_SHIFT 12 /**< Shift value for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_MASK 0x1F000UL /**< Bit mask for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_SUDELAY_DEFAULT (_CMU_HFRCOCTRL_SUDELAY_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-
-/* Bit fields for CMU LFRCOCTRL */
-#define _CMU_LFRCOCTRL_RESETVALUE 0x00000040UL /**< Default value for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_MASK 0x0000007FUL /**< Mask for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_MASK 0x7FUL /**< Bit mask for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_DEFAULT 0x00000040UL /**< Mode DEFAULT for CMU_LFRCOCTRL */
-#define CMU_LFRCOCTRL_TUNING_DEFAULT (_CMU_LFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFRCOCTRL */
-
-/* Bit fields for CMU AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_RESETVALUE 0x00000080UL /**< Default value for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_MASK 0x000007FFUL /**< Mask for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_TUNING_DEFAULT (_CMU_AUXHFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_14MHZ 0x00000000UL /**< Mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_11MHZ 0x00000001UL /**< Mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_7MHZ 0x00000002UL /**< Mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_1MHZ 0x00000003UL /**< Mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_21MHZ 0x00000007UL /**< Mode 21MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_DEFAULT (_CMU_AUXHFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_14MHZ (_CMU_AUXHFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_11MHZ (_CMU_AUXHFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_7MHZ (_CMU_AUXHFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_1MHZ (_CMU_AUXHFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_21MHZ (_CMU_AUXHFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_AUXHFRCOCTRL */
-
-/* Bit fields for CMU CALCTRL */
-#define _CMU_CALCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCTRL */
-#define _CMU_CALCTRL_MASK 0x0000007FUL /**< Mask for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_SHIFT 0 /**< Shift value for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_MASK 0x7UL /**< Bit mask for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFXO 0x00000000UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFXO 0x00000001UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFRCO 0x00000002UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_AUXHFRCO 0x00000004UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_DEFAULT (_CMU_CALCTRL_UPSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFXO (_CMU_CALCTRL_UPSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFXO (_CMU_CALCTRL_UPSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFRCO (_CMU_CALCTRL_UPSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFRCO (_CMU_CALCTRL_UPSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_AUXHFRCO (_CMU_CALCTRL_UPSEL_AUXHFRCO << 0) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_SHIFT 3 /**< Shift value for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_MASK 0x38UL /**< Bit mask for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFXO 0x00000001UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFXO 0x00000002UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFRCO 0x00000003UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFRCO 0x00000004UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_AUXHFRCO 0x00000005UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_DEFAULT (_CMU_CALCTRL_DOWNSEL_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFCLK (_CMU_CALCTRL_DOWNSEL_HFCLK << 3) /**< Shifted mode HFCLK for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFXO (_CMU_CALCTRL_DOWNSEL_HFXO << 3) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFXO (_CMU_CALCTRL_DOWNSEL_LFXO << 3) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFRCO (_CMU_CALCTRL_DOWNSEL_HFRCO << 3) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFRCO (_CMU_CALCTRL_DOWNSEL_LFRCO << 3) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_AUXHFRCO (_CMU_CALCTRL_DOWNSEL_AUXHFRCO << 3) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT (0x1UL << 6) /**< Continuous Calibration */
-#define _CMU_CALCTRL_CONT_SHIFT 6 /**< Shift value for CMU_CONT */
-#define _CMU_CALCTRL_CONT_MASK 0x40UL /**< Bit mask for CMU_CONT */
-#define _CMU_CALCTRL_CONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT_DEFAULT (_CMU_CALCTRL_CONT_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-
-/* Bit fields for CMU CALCNT */
-#define _CMU_CALCNT_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCNT */
-#define _CMU_CALCNT_MASK 0x000FFFFFUL /**< Mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_SHIFT 0 /**< Shift value for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_MASK 0xFFFFFUL /**< Bit mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCNT */
-#define CMU_CALCNT_CALCNT_DEFAULT (_CMU_CALCNT_CALCNT_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCNT */
-
-/* Bit fields for CMU OSCENCMD */
-#define _CMU_OSCENCMD_RESETVALUE 0x00000000UL /**< Default value for CMU_OSCENCMD */
-#define _CMU_OSCENCMD_MASK 0x000003FFUL /**< Mask for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN (0x1UL << 0) /**< HFRCO Enable */
-#define _CMU_OSCENCMD_HFRCOEN_SHIFT 0 /**< Shift value for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_MASK 0x1UL /**< Bit mask for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN_DEFAULT (_CMU_OSCENCMD_HFRCOEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS (0x1UL << 1) /**< HFRCO Disable */
-#define _CMU_OSCENCMD_HFRCODIS_SHIFT 1 /**< Shift value for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_MASK 0x2UL /**< Bit mask for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS_DEFAULT (_CMU_OSCENCMD_HFRCODIS_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN (0x1UL << 2) /**< HFXO Enable */
-#define _CMU_OSCENCMD_HFXOEN_SHIFT 2 /**< Shift value for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_MASK 0x4UL /**< Bit mask for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN_DEFAULT (_CMU_OSCENCMD_HFXOEN_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS (0x1UL << 3) /**< HFXO Disable */
-#define _CMU_OSCENCMD_HFXODIS_SHIFT 3 /**< Shift value for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_MASK 0x8UL /**< Bit mask for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS_DEFAULT (_CMU_OSCENCMD_HFXODIS_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN (0x1UL << 4) /**< AUXHFRCO Enable */
-#define _CMU_OSCENCMD_AUXHFRCOEN_SHIFT 4 /**< Shift value for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN_DEFAULT (_CMU_OSCENCMD_AUXHFRCOEN_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS (0x1UL << 5) /**< AUXHFRCO Disable */
-#define _CMU_OSCENCMD_AUXHFRCODIS_SHIFT 5 /**< Shift value for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS_DEFAULT (_CMU_OSCENCMD_AUXHFRCODIS_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN (0x1UL << 6) /**< LFRCO Enable */
-#define _CMU_OSCENCMD_LFRCOEN_SHIFT 6 /**< Shift value for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_MASK 0x40UL /**< Bit mask for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN_DEFAULT (_CMU_OSCENCMD_LFRCOEN_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS (0x1UL << 7) /**< LFRCO Disable */
-#define _CMU_OSCENCMD_LFRCODIS_SHIFT 7 /**< Shift value for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_MASK 0x80UL /**< Bit mask for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS_DEFAULT (_CMU_OSCENCMD_LFRCODIS_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN (0x1UL << 8) /**< LFXO Enable */
-#define _CMU_OSCENCMD_LFXOEN_SHIFT 8 /**< Shift value for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_MASK 0x100UL /**< Bit mask for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN_DEFAULT (_CMU_OSCENCMD_LFXOEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS (0x1UL << 9) /**< LFXO Disable */
-#define _CMU_OSCENCMD_LFXODIS_SHIFT 9 /**< Shift value for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_MASK 0x200UL /**< Bit mask for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS_DEFAULT (_CMU_OSCENCMD_LFXODIS_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-
-/* Bit fields for CMU CMD */
-#define _CMU_CMD_RESETVALUE 0x00000000UL /**< Default value for CMU_CMD */
-#define _CMU_CMD_MASK 0x0000001FUL /**< Mask for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_SHIFT 0 /**< Shift value for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_MASK 0x7UL /**< Bit mask for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFRCO 0x00000001UL /**< Mode HFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFXO 0x00000002UL /**< Mode HFXO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFXO 0x00000004UL /**< Mode LFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_DEFAULT (_CMU_CMD_HFCLKSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFRCO (_CMU_CMD_HFCLKSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFXO (_CMU_CMD_HFCLKSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFRCO (_CMU_CMD_HFCLKSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFXO (_CMU_CMD_HFCLKSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CMD */
-#define CMU_CMD_CALSTART (0x1UL << 3) /**< Calibration Start */
-#define _CMU_CMD_CALSTART_SHIFT 3 /**< Shift value for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_MASK 0x8UL /**< Bit mask for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTART_DEFAULT (_CMU_CMD_CALSTART_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP (0x1UL << 4) /**< Calibration Stop */
-#define _CMU_CMD_CALSTOP_SHIFT 4 /**< Shift value for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_MASK 0x10UL /**< Bit mask for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP_DEFAULT (_CMU_CMD_CALSTOP_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_CMD */
-
-/* Bit fields for CMU LFCLKSEL */
-#define _CMU_LFCLKSEL_RESETVALUE 0x00000005UL /**< Default value for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_MASK 0x0011000FUL /**< Mask for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_SHIFT 0 /**< Shift value for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_MASK 0x3UL /**< Bit mask for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DISABLED (_CMU_LFCLKSEL_LFA_DISABLED << 0) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DEFAULT (_CMU_LFCLKSEL_LFA_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFRCO (_CMU_LFCLKSEL_LFA_LFRCO << 0) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFXO (_CMU_LFCLKSEL_LFA_LFXO << 0) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 << 0) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_SHIFT 2 /**< Shift value for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_MASK 0xCUL /**< Bit mask for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DISABLED (_CMU_LFCLKSEL_LFB_DISABLED << 2) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DEFAULT (_CMU_LFCLKSEL_LFB_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFRCO (_CMU_LFCLKSEL_LFB_LFRCO << 2) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFXO (_CMU_LFCLKSEL_LFB_LFXO << 2) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 << 2) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE (0x1UL << 16) /**< Clock Select for LFA Extended */
-#define _CMU_LFCLKSEL_LFAE_SHIFT 16 /**< Shift value for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_MASK 0x10000UL /**< Bit mask for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DEFAULT (_CMU_LFCLKSEL_LFAE_DEFAULT << 16) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DISABLED (_CMU_LFCLKSEL_LFAE_DISABLED << 16) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_ULFRCO (_CMU_LFCLKSEL_LFAE_ULFRCO << 16) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE (0x1UL << 20) /**< Clock Select for LFB Extended */
-#define _CMU_LFCLKSEL_LFBE_SHIFT 20 /**< Shift value for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_MASK 0x100000UL /**< Bit mask for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DEFAULT (_CMU_LFCLKSEL_LFBE_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DISABLED (_CMU_LFCLKSEL_LFBE_DISABLED << 20) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_ULFRCO (_CMU_LFCLKSEL_LFBE_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-
-/* Bit fields for CMU STATUS */
-#define _CMU_STATUS_RESETVALUE 0x00000403UL /**< Default value for CMU_STATUS */
-#define _CMU_STATUS_MASK 0x00007FFFUL /**< Mask for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS (0x1UL << 0) /**< HFRCO Enable Status */
-#define _CMU_STATUS_HFRCOENS_SHIFT 0 /**< Shift value for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_MASK 0x1UL /**< Bit mask for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS_DEFAULT (_CMU_STATUS_HFRCOENS_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY (0x1UL << 1) /**< HFRCO Ready */
-#define _CMU_STATUS_HFRCORDY_SHIFT 1 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_MASK 0x2UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY_DEFAULT (_CMU_STATUS_HFRCORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS (0x1UL << 2) /**< HFXO Enable Status */
-#define _CMU_STATUS_HFXOENS_SHIFT 2 /**< Shift value for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_MASK 0x4UL /**< Bit mask for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS_DEFAULT (_CMU_STATUS_HFXOENS_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY (0x1UL << 3) /**< HFXO Ready */
-#define _CMU_STATUS_HFXORDY_SHIFT 3 /**< Shift value for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_MASK 0x8UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY_DEFAULT (_CMU_STATUS_HFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS (0x1UL << 4) /**< AUXHFRCO Enable Status */
-#define _CMU_STATUS_AUXHFRCOENS_SHIFT 4 /**< Shift value for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS_DEFAULT (_CMU_STATUS_AUXHFRCOENS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY (0x1UL << 5) /**< AUXHFRCO Ready */
-#define _CMU_STATUS_AUXHFRCORDY_SHIFT 5 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY_DEFAULT (_CMU_STATUS_AUXHFRCORDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS (0x1UL << 6) /**< LFRCO Enable Status */
-#define _CMU_STATUS_LFRCOENS_SHIFT 6 /**< Shift value for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_MASK 0x40UL /**< Bit mask for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS_DEFAULT (_CMU_STATUS_LFRCOENS_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY (0x1UL << 7) /**< LFRCO Ready */
-#define _CMU_STATUS_LFRCORDY_SHIFT 7 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_MASK 0x80UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY_DEFAULT (_CMU_STATUS_LFRCORDY_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS (0x1UL << 8) /**< LFXO Enable Status */
-#define _CMU_STATUS_LFXOENS_SHIFT 8 /**< Shift value for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_MASK 0x100UL /**< Bit mask for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS_DEFAULT (_CMU_STATUS_LFXOENS_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY (0x1UL << 9) /**< LFXO Ready */
-#define _CMU_STATUS_LFXORDY_SHIFT 9 /**< Shift value for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_MASK 0x200UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY_DEFAULT (_CMU_STATUS_LFXORDY_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL (0x1UL << 10) /**< HFRCO Selected */
-#define _CMU_STATUS_HFRCOSEL_SHIFT 10 /**< Shift value for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_MASK 0x400UL /**< Bit mask for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL_DEFAULT (_CMU_STATUS_HFRCOSEL_DEFAULT << 10) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL (0x1UL << 11) /**< HFXO Selected */
-#define _CMU_STATUS_HFXOSEL_SHIFT 11 /**< Shift value for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_MASK 0x800UL /**< Bit mask for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL_DEFAULT (_CMU_STATUS_HFXOSEL_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL (0x1UL << 12) /**< LFRCO Selected */
-#define _CMU_STATUS_LFRCOSEL_SHIFT 12 /**< Shift value for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_MASK 0x1000UL /**< Bit mask for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL_DEFAULT (_CMU_STATUS_LFRCOSEL_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL (0x1UL << 13) /**< LFXO Selected */
-#define _CMU_STATUS_LFXOSEL_SHIFT 13 /**< Shift value for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_MASK 0x2000UL /**< Bit mask for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL_DEFAULT (_CMU_STATUS_LFXOSEL_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY (0x1UL << 14) /**< Calibration Busy */
-#define _CMU_STATUS_CALBSY_SHIFT 14 /**< Shift value for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_MASK 0x4000UL /**< Bit mask for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY_DEFAULT (_CMU_STATUS_CALBSY_DEFAULT << 14) /**< Shifted mode DEFAULT for CMU_STATUS */
-
-/* Bit fields for CMU IF */
-#define _CMU_IF_RESETVALUE 0x00000001UL /**< Default value for CMU_IF */
-#define _CMU_IF_MASK 0x0000007FUL /**< Mask for CMU_IF */
-#define CMU_IF_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag */
-#define _CMU_IF_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFRCORDY_DEFAULT (_CMU_IF_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag */
-#define _CMU_IF_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY_DEFAULT (_CMU_IF_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag */
-#define _CMU_IF_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY_DEFAULT (_CMU_IF_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag */
-#define _CMU_IF_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY_DEFAULT (_CMU_IF_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag */
-#define _CMU_IF_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY_DEFAULT (_CMU_IF_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag */
-#define _CMU_IF_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IF_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IF_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY_DEFAULT (_CMU_IF_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag */
-#define _CMU_IF_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IF_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IF_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF_DEFAULT (_CMU_IF_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IF */
-
-/* Bit fields for CMU IFS */
-#define _CMU_IFS_RESETVALUE 0x00000000UL /**< Default value for CMU_IFS */
-#define _CMU_IFS_MASK 0x0000007FUL /**< Mask for CMU_IFS */
-#define CMU_IFS_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFRCORDY_DEFAULT (_CMU_IFS_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY_DEFAULT (_CMU_IFS_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY_DEFAULT (_CMU_IFS_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY_DEFAULT (_CMU_IFS_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY_DEFAULT (_CMU_IFS_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Set */
-#define _CMU_IFS_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY_DEFAULT (_CMU_IFS_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Set */
-#define _CMU_IFS_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFS_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFS_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF_DEFAULT (_CMU_IFS_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFS */
-
-/* Bit fields for CMU IFC */
-#define _CMU_IFC_RESETVALUE 0x00000000UL /**< Default value for CMU_IFC */
-#define _CMU_IFC_MASK 0x0000007FUL /**< Mask for CMU_IFC */
-#define CMU_IFC_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFRCORDY_DEFAULT (_CMU_IFC_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY_DEFAULT (_CMU_IFC_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY_DEFAULT (_CMU_IFC_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY_DEFAULT (_CMU_IFC_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY_DEFAULT (_CMU_IFC_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Clear */
-#define _CMU_IFC_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY_DEFAULT (_CMU_IFC_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Clear */
-#define _CMU_IFC_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFC_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFC_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF_DEFAULT (_CMU_IFC_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFC */
-
-/* Bit fields for CMU IEN */
-#define _CMU_IEN_RESETVALUE 0x00000000UL /**< Default value for CMU_IEN */
-#define _CMU_IEN_MASK 0x0000007FUL /**< Mask for CMU_IEN */
-#define CMU_IEN_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Enable */
-#define _CMU_IEN_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFRCORDY_DEFAULT (_CMU_IEN_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Enable */
-#define _CMU_IEN_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY_DEFAULT (_CMU_IEN_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Enable */
-#define _CMU_IEN_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY_DEFAULT (_CMU_IEN_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Enable */
-#define _CMU_IEN_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY_DEFAULT (_CMU_IEN_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Enable */
-#define _CMU_IEN_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY_DEFAULT (_CMU_IEN_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Enable */
-#define _CMU_IEN_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY_DEFAULT (_CMU_IEN_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Enable */
-#define _CMU_IEN_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IEN_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IEN_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF_DEFAULT (_CMU_IEN_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IEN */
-
-/* Bit fields for CMU HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_MASK 0x00000006UL /**< Mask for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA (0x1UL << 1) /**< Direct Memory Access Controller Clock Enable */
-#define _CMU_HFCORECLKEN0_DMA_SHIFT 1 /**< Shift value for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_MASK 0x2UL /**< Bit mask for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA_DEFAULT (_CMU_HFCORECLKEN0_DMA_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE (0x1UL << 2) /**< Low Energy Peripheral Interface Clock Enable */
-#define _CMU_HFCORECLKEN0_LE_SHIFT 2 /**< Shift value for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_MASK 0x4UL /**< Bit mask for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE_DEFAULT (_CMU_HFCORECLKEN0_LE_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-
-/* Bit fields for CMU HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_MASK 0x0000099FUL /**< Mask for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0 (0x1UL << 0) /**< Timer 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER0_SHIFT 0 /**< Shift value for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_MASK 0x1UL /**< Bit mask for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0_DEFAULT (_CMU_HFPERCLKEN0_TIMER0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1 (0x1UL << 1) /**< Timer 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER1_SHIFT 1 /**< Shift value for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_MASK 0x2UL /**< Bit mask for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1_DEFAULT (_CMU_HFPERCLKEN0_TIMER1_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0 (0x1UL << 2) /**< Analog Comparator 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_ACMP0_SHIFT 2 /**< Shift value for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_MASK 0x4UL /**< Bit mask for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0_DEFAULT (_CMU_HFPERCLKEN0_ACMP0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1 (0x1UL << 3) /**< Universal Synchronous/Asynchronous Receiver/Transmitter 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_USART1_SHIFT 3 /**< Shift value for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_MASK 0x8UL /**< Bit mask for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1_DEFAULT (_CMU_HFPERCLKEN0_USART1_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS (0x1UL << 4) /**< Peripheral Reflex System Clock Enable */
-#define _CMU_HFPERCLKEN0_PRS_SHIFT 4 /**< Shift value for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_MASK 0x10UL /**< Bit mask for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS_DEFAULT (_CMU_HFPERCLKEN0_PRS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO (0x1UL << 7) /**< General purpose Input/Output Clock Enable */
-#define _CMU_HFPERCLKEN0_GPIO_SHIFT 7 /**< Shift value for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_MASK 0x80UL /**< Bit mask for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO_DEFAULT (_CMU_HFPERCLKEN0_GPIO_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP (0x1UL << 8) /**< Voltage Comparator Clock Enable */
-#define _CMU_HFPERCLKEN0_VCMP_SHIFT 8 /**< Shift value for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_MASK 0x100UL /**< Bit mask for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP_DEFAULT (_CMU_HFPERCLKEN0_VCMP_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0 (0x1UL << 11) /**< I2C 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_I2C0_SHIFT 11 /**< Shift value for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_MASK 0x800UL /**< Bit mask for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0_DEFAULT (_CMU_HFPERCLKEN0_I2C0_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-
-/* Bit fields for CMU SYNCBUSY */
-#define _CMU_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for CMU_SYNCBUSY */
-#define _CMU_SYNCBUSY_MASK 0x00000055UL /**< Mask for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0 (0x1UL << 0) /**< Low Frequency A Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFACLKEN0_SHIFT 0 /**< Shift value for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_MASK 0x1UL /**< Bit mask for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0_DEFAULT (_CMU_SYNCBUSY_LFACLKEN0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0 (0x1UL << 2) /**< Low Frequency A Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFAPRESC0_SHIFT 2 /**< Shift value for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_MASK 0x4UL /**< Bit mask for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0_DEFAULT (_CMU_SYNCBUSY_LFAPRESC0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0 (0x1UL << 4) /**< Low Frequency B Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFBCLKEN0_SHIFT 4 /**< Shift value for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_MASK 0x10UL /**< Bit mask for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0_DEFAULT (_CMU_SYNCBUSY_LFBCLKEN0_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0 (0x1UL << 6) /**< Low Frequency B Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFBPRESC0_SHIFT 6 /**< Shift value for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_MASK 0x40UL /**< Bit mask for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0_DEFAULT (_CMU_SYNCBUSY_LFBPRESC0_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-
-/* Bit fields for CMU FREEZE */
-#define _CMU_FREEZE_RESETVALUE 0x00000000UL /**< Default value for CMU_FREEZE */
-#define _CMU_FREEZE_MASK 0x00000001UL /**< Mask for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _CMU_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_DEFAULT (_CMU_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_UPDATE (_CMU_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_FREEZE (_CMU_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for CMU_FREEZE */
-
-/* Bit fields for CMU LFACLKEN0 */
-#define _CMU_LFACLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFACLKEN0 */
-#define _CMU_LFACLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC (0x1UL << 0) /**< Real-Time Counter Clock Enable */
-#define _CMU_LFACLKEN0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_MASK 0x1UL /**< Bit mask for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC_DEFAULT (_CMU_LFACLKEN0_RTC_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFACLKEN0 */
-
-/* Bit fields for CMU LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0 (0x1UL << 0) /**< Low Energy UART 0 Clock Enable */
-#define _CMU_LFBCLKEN0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_MASK 0x1UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0_DEFAULT (_CMU_LFBCLKEN0_LEUART0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFBCLKEN0 */
-
-/* Bit fields for CMU LFAPRESC0 */
-#define _CMU_LFAPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_MASK 0x0000000FUL /**< Mask for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_MASK 0xFUL /**< Bit mask for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16 0x00000004UL /**< Mode DIV16 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32 0x00000005UL /**< Mode DIV32 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV64 0x00000006UL /**< Mode DIV64 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV128 0x00000007UL /**< Mode DIV128 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV256 0x00000008UL /**< Mode DIV256 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV512 0x00000009UL /**< Mode DIV512 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV1024 0x0000000AUL /**< Mode DIV1024 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2048 0x0000000BUL /**< Mode DIV2048 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4096 0x0000000CUL /**< Mode DIV4096 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8192 0x0000000DUL /**< Mode DIV8192 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16384 0x0000000EUL /**< Mode DIV16384 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32768 0x0000000FUL /**< Mode DIV32768 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1 (_CMU_LFAPRESC0_RTC_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2 (_CMU_LFAPRESC0_RTC_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4 (_CMU_LFAPRESC0_RTC_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8 (_CMU_LFAPRESC0_RTC_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16 (_CMU_LFAPRESC0_RTC_DIV16 << 0) /**< Shifted mode DIV16 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32 (_CMU_LFAPRESC0_RTC_DIV32 << 0) /**< Shifted mode DIV32 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV64 (_CMU_LFAPRESC0_RTC_DIV64 << 0) /**< Shifted mode DIV64 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV128 (_CMU_LFAPRESC0_RTC_DIV128 << 0) /**< Shifted mode DIV128 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV256 (_CMU_LFAPRESC0_RTC_DIV256 << 0) /**< Shifted mode DIV256 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV512 (_CMU_LFAPRESC0_RTC_DIV512 << 0) /**< Shifted mode DIV512 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1024 (_CMU_LFAPRESC0_RTC_DIV1024 << 0) /**< Shifted mode DIV1024 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2048 (_CMU_LFAPRESC0_RTC_DIV2048 << 0) /**< Shifted mode DIV2048 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4096 (_CMU_LFAPRESC0_RTC_DIV4096 << 0) /**< Shifted mode DIV4096 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8192 (_CMU_LFAPRESC0_RTC_DIV8192 << 0) /**< Shifted mode DIV8192 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16384 (_CMU_LFAPRESC0_RTC_DIV16384 << 0) /**< Shifted mode DIV16384 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32768 (_CMU_LFAPRESC0_RTC_DIV32768 << 0) /**< Shifted mode DIV32768 for CMU_LFAPRESC0 */
-
-/* Bit fields for CMU LFBPRESC0 */
-#define _CMU_LFBPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_MASK 0x00000003UL /**< Mask for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_MASK 0x3UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV1 (_CMU_LFBPRESC0_LEUART0_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV2 (_CMU_LFBPRESC0_LEUART0_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV4 (_CMU_LFBPRESC0_LEUART0_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV8 (_CMU_LFBPRESC0_LEUART0_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFBPRESC0 */
-
-/* Bit fields for CMU PCNTCTRL */
-#define _CMU_PCNTCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_MASK 0x00000003UL /**< Mask for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN (0x1UL << 0) /**< PCNT0 Clock Enable */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_SHIFT 0 /**< Shift value for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_MASK 0x1UL /**< Bit mask for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL (0x1UL << 1) /**< PCNT0 Clock Select */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_SHIFT 1 /**< Shift value for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_MASK 0x2UL /**< Bit mask for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK 0x00000000UL /**< Mode LFACLK for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 0x00000001UL /**< Mode PCNT0S0 for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK (_CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK << 1) /**< Shifted mode LFACLK for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 (_CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 << 1) /**< Shifted mode PCNT0S0 for CMU_PCNTCTRL */
-
-/* Bit fields for CMU ROUTE */
-#define _CMU_ROUTE_RESETVALUE 0x00000000UL /**< Default value for CMU_ROUTE */
-#define _CMU_ROUTE_MASK 0x0000001FUL /**< Mask for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN (0x1UL << 0) /**< CLKOUT0 Pin Enable */
-#define _CMU_ROUTE_CLKOUT0PEN_SHIFT 0 /**< Shift value for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_MASK 0x1UL /**< Bit mask for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN_DEFAULT (_CMU_ROUTE_CLKOUT0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN (0x1UL << 1) /**< CLKOUT1 Pin Enable */
-#define _CMU_ROUTE_CLKOUT1PEN_SHIFT 1 /**< Shift value for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_MASK 0x2UL /**< Bit mask for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN_DEFAULT (_CMU_ROUTE_CLKOUT1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_SHIFT 2 /**< Shift value for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_MASK 0x1CUL /**< Bit mask for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC0 (_CMU_ROUTE_LOCATION_LOC0 << 2) /**< Shifted mode LOC0 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_DEFAULT (_CMU_ROUTE_LOCATION_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC1 (_CMU_ROUTE_LOCATION_LOC1 << 2) /**< Shifted mode LOC1 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC2 (_CMU_ROUTE_LOCATION_LOC2 << 2) /**< Shifted mode LOC2 for CMU_ROUTE */
-
-/* Bit fields for CMU LOCK */
-#define _CMU_LOCK_RESETVALUE 0x00000000UL /**< Default value for CMU_LOCK */
-#define _CMU_LOCK_MASK 0x0000FFFFUL /**< Mask for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCK 0x0000580EUL /**< Mode UNLOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_DEFAULT (_CMU_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCK (_CMU_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCKED (_CMU_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCKED (_CMU_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCK (_CMU_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for CMU_LOCK */
-
-/** @} End of group EFM32ZG108F16_CMU */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_PRS_BitFields EFM32ZG108F16_PRS Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for PRS SWPULSE */
-#define _PRS_SWPULSE_RESETVALUE 0x00000000UL /**< Default value for PRS_SWPULSE */
-#define _PRS_SWPULSE_MASK 0x0000000FUL /**< Mask for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE (0x1UL << 0) /**< Channel 0 Pulse Generation */
-#define _PRS_SWPULSE_CH0PULSE_SHIFT 0 /**< Shift value for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_MASK 0x1UL /**< Bit mask for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE_DEFAULT (_PRS_SWPULSE_CH0PULSE_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE (0x1UL << 1) /**< Channel 1 Pulse Generation */
-#define _PRS_SWPULSE_CH1PULSE_SHIFT 1 /**< Shift value for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_MASK 0x2UL /**< Bit mask for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE_DEFAULT (_PRS_SWPULSE_CH1PULSE_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE (0x1UL << 2) /**< Channel 2 Pulse Generation */
-#define _PRS_SWPULSE_CH2PULSE_SHIFT 2 /**< Shift value for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_MASK 0x4UL /**< Bit mask for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE_DEFAULT (_PRS_SWPULSE_CH2PULSE_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE (0x1UL << 3) /**< Channel 3 Pulse Generation */
-#define _PRS_SWPULSE_CH3PULSE_SHIFT 3 /**< Shift value for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_MASK 0x8UL /**< Bit mask for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE_DEFAULT (_PRS_SWPULSE_CH3PULSE_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-
-/* Bit fields for PRS SWLEVEL */
-#define _PRS_SWLEVEL_RESETVALUE 0x00000000UL /**< Default value for PRS_SWLEVEL */
-#define _PRS_SWLEVEL_MASK 0x0000000FUL /**< Mask for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL (0x1UL << 0) /**< Channel 0 Software Level */
-#define _PRS_SWLEVEL_CH0LEVEL_SHIFT 0 /**< Shift value for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_MASK 0x1UL /**< Bit mask for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL_DEFAULT (_PRS_SWLEVEL_CH0LEVEL_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL (0x1UL << 1) /**< Channel 1 Software Level */
-#define _PRS_SWLEVEL_CH1LEVEL_SHIFT 1 /**< Shift value for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_MASK 0x2UL /**< Bit mask for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL_DEFAULT (_PRS_SWLEVEL_CH1LEVEL_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL (0x1UL << 2) /**< Channel 2 Software Level */
-#define _PRS_SWLEVEL_CH2LEVEL_SHIFT 2 /**< Shift value for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_MASK 0x4UL /**< Bit mask for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL_DEFAULT (_PRS_SWLEVEL_CH2LEVEL_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL (0x1UL << 3) /**< Channel 3 Software Level */
-#define _PRS_SWLEVEL_CH3LEVEL_SHIFT 3 /**< Shift value for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_MASK 0x8UL /**< Bit mask for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL_DEFAULT (_PRS_SWLEVEL_CH3LEVEL_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-
-/* Bit fields for PRS ROUTE */
-#define _PRS_ROUTE_RESETVALUE 0x00000000UL /**< Default value for PRS_ROUTE */
-#define _PRS_ROUTE_MASK 0x0000070FUL /**< Mask for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN (0x1UL << 0) /**< CH0 Pin Enable */
-#define _PRS_ROUTE_CH0PEN_SHIFT 0 /**< Shift value for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_MASK 0x1UL /**< Bit mask for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN_DEFAULT (_PRS_ROUTE_CH0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN (0x1UL << 1) /**< CH1 Pin Enable */
-#define _PRS_ROUTE_CH1PEN_SHIFT 1 /**< Shift value for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_MASK 0x2UL /**< Bit mask for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN_DEFAULT (_PRS_ROUTE_CH1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN (0x1UL << 2) /**< CH2 Pin Enable */
-#define _PRS_ROUTE_CH2PEN_SHIFT 2 /**< Shift value for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_MASK 0x4UL /**< Bit mask for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN_DEFAULT (_PRS_ROUTE_CH2PEN_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN (0x1UL << 3) /**< CH3 Pin Enable */
-#define _PRS_ROUTE_CH3PEN_SHIFT 3 /**< Shift value for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_MASK 0x8UL /**< Bit mask for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN_DEFAULT (_PRS_ROUTE_CH3PEN_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_SHIFT 8 /**< Shift value for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC0 (_PRS_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_DEFAULT (_PRS_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC1 (_PRS_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC2 (_PRS_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for PRS_ROUTE */
-
-/* Bit fields for PRS CH_CTRL */
-#define _PRS_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_MASK 0x133F0007UL /**< Mask for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_MASK 0x7UL /**< Bit mask for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_VCMPOUT 0x00000000UL /**< Mode VCMPOUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ACMP0OUT 0x00000000UL /**< Mode ACMP0OUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1IRTX 0x00000000UL /**< Mode USART1IRTX for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0UF 0x00000000UL /**< Mode TIMER0UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1UF 0x00000000UL /**< Mode TIMER1UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCOF 0x00000000UL /**< Mode RTCOF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN0 0x00000000UL /**< Mode GPIOPIN0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN8 0x00000000UL /**< Mode GPIOPIN8 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_PCNT0TCC 0x00000000UL /**< Mode PCNT0TCC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1TXC 0x00000001UL /**< Mode USART1TXC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0OF 0x00000001UL /**< Mode TIMER0OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1OF 0x00000001UL /**< Mode TIMER1OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP0 0x00000001UL /**< Mode RTCCOMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN1 0x00000001UL /**< Mode GPIOPIN1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN9 0x00000001UL /**< Mode GPIOPIN9 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000002UL /**< Mode USART1RXDATAV for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC0 0x00000002UL /**< Mode TIMER0CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC0 0x00000002UL /**< Mode TIMER1CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP1 0x00000002UL /**< Mode RTCCOMP1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN2 0x00000002UL /**< Mode GPIOPIN2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN10 0x00000002UL /**< Mode GPIOPIN10 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC1 0x00000003UL /**< Mode TIMER0CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC1 0x00000003UL /**< Mode TIMER1CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN3 0x00000003UL /**< Mode GPIOPIN3 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN11 0x00000003UL /**< Mode GPIOPIN11 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC2 0x00000004UL /**< Mode TIMER0CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC2 0x00000004UL /**< Mode TIMER1CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN4 0x00000004UL /**< Mode GPIOPIN4 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN12 0x00000004UL /**< Mode GPIOPIN12 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN5 0x00000005UL /**< Mode GPIOPIN5 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN13 0x00000005UL /**< Mode GPIOPIN13 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN6 0x00000006UL /**< Mode GPIOPIN6 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN14 0x00000006UL /**< Mode GPIOPIN14 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN7 0x00000007UL /**< Mode GPIOPIN7 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN15 0x00000007UL /**< Mode GPIOPIN15 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_VCMPOUT (_PRS_CH_CTRL_SIGSEL_VCMPOUT << 0) /**< Shifted mode VCMPOUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ACMP0OUT (_PRS_CH_CTRL_SIGSEL_ACMP0OUT << 0) /**< Shifted mode ACMP0OUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1IRTX (_PRS_CH_CTRL_SIGSEL_USART1IRTX << 0) /**< Shifted mode USART1IRTX for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0UF (_PRS_CH_CTRL_SIGSEL_TIMER0UF << 0) /**< Shifted mode TIMER0UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1UF (_PRS_CH_CTRL_SIGSEL_TIMER1UF << 0) /**< Shifted mode TIMER1UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCOF (_PRS_CH_CTRL_SIGSEL_RTCOF << 0) /**< Shifted mode RTCOF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN0 (_PRS_CH_CTRL_SIGSEL_GPIOPIN0 << 0) /**< Shifted mode GPIOPIN0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN8 (_PRS_CH_CTRL_SIGSEL_GPIOPIN8 << 0) /**< Shifted mode GPIOPIN8 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_PCNT0TCC (_PRS_CH_CTRL_SIGSEL_PCNT0TCC << 0) /**< Shifted mode PCNT0TCC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1TXC (_PRS_CH_CTRL_SIGSEL_USART1TXC << 0) /**< Shifted mode USART1TXC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0OF (_PRS_CH_CTRL_SIGSEL_TIMER0OF << 0) /**< Shifted mode TIMER0OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1OF (_PRS_CH_CTRL_SIGSEL_TIMER1OF << 0) /**< Shifted mode TIMER1OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP0 (_PRS_CH_CTRL_SIGSEL_RTCCOMP0 << 0) /**< Shifted mode RTCCOMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN1 (_PRS_CH_CTRL_SIGSEL_GPIOPIN1 << 0) /**< Shifted mode GPIOPIN1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN9 (_PRS_CH_CTRL_SIGSEL_GPIOPIN9 << 0) /**< Shifted mode GPIOPIN9 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1RXDATAV (_PRS_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC0 (_PRS_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC0 (_PRS_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP1 (_PRS_CH_CTRL_SIGSEL_RTCCOMP1 << 0) /**< Shifted mode RTCCOMP1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN2 (_PRS_CH_CTRL_SIGSEL_GPIOPIN2 << 0) /**< Shifted mode GPIOPIN2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN10 (_PRS_CH_CTRL_SIGSEL_GPIOPIN10 << 0) /**< Shifted mode GPIOPIN10 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC1 (_PRS_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC1 (_PRS_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN3 (_PRS_CH_CTRL_SIGSEL_GPIOPIN3 << 0) /**< Shifted mode GPIOPIN3 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN11 (_PRS_CH_CTRL_SIGSEL_GPIOPIN11 << 0) /**< Shifted mode GPIOPIN11 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC2 (_PRS_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC2 (_PRS_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN4 (_PRS_CH_CTRL_SIGSEL_GPIOPIN4 << 0) /**< Shifted mode GPIOPIN4 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN12 (_PRS_CH_CTRL_SIGSEL_GPIOPIN12 << 0) /**< Shifted mode GPIOPIN12 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN5 (_PRS_CH_CTRL_SIGSEL_GPIOPIN5 << 0) /**< Shifted mode GPIOPIN5 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN13 (_PRS_CH_CTRL_SIGSEL_GPIOPIN13 << 0) /**< Shifted mode GPIOPIN13 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN6 (_PRS_CH_CTRL_SIGSEL_GPIOPIN6 << 0) /**< Shifted mode GPIOPIN6 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN14 (_PRS_CH_CTRL_SIGSEL_GPIOPIN14 << 0) /**< Shifted mode GPIOPIN14 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN7 (_PRS_CH_CTRL_SIGSEL_GPIOPIN7 << 0) /**< Shifted mode GPIOPIN7 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN15 (_PRS_CH_CTRL_SIGSEL_GPIOPIN15 << 0) /**< Shifted mode GPIOPIN15 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_VCMP 0x00000001UL /**< Mode VCMP for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_ACMP0 0x00000002UL /**< Mode ACMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_USART1 0x00000011UL /**< Mode USART1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER0 0x0000001CUL /**< Mode TIMER0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER1 0x0000001DUL /**< Mode TIMER1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_RTC 0x00000028UL /**< Mode RTC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOL 0x00000030UL /**< Mode GPIOL for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOH 0x00000031UL /**< Mode GPIOH for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_PCNT0 0x00000036UL /**< Mode PCNT0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_NONE (_PRS_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_VCMP (_PRS_CH_CTRL_SOURCESEL_VCMP << 16) /**< Shifted mode VCMP for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_ACMP0 (_PRS_CH_CTRL_SOURCESEL_ACMP0 << 16) /**< Shifted mode ACMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_USART1 (_PRS_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER0 (_PRS_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER1 (_PRS_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_RTC (_PRS_CH_CTRL_SOURCESEL_RTC << 16) /**< Shifted mode RTC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOL (_PRS_CH_CTRL_SOURCESEL_GPIOL << 16) /**< Shifted mode GPIOL for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOH (_PRS_CH_CTRL_SOURCESEL_GPIOH << 16) /**< Shifted mode GPIOH for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_PCNT0 (_PRS_CH_CTRL_SOURCESEL_PCNT0 << 16) /**< Shifted mode PCNT0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_SHIFT 24 /**< Shift value for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_MASK 0x3000000UL /**< Bit mask for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_OFF 0x00000000UL /**< Mode OFF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_POSEDGE 0x00000001UL /**< Mode POSEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_NEGEDGE 0x00000002UL /**< Mode NEGEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_BOTHEDGES 0x00000003UL /**< Mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_DEFAULT (_PRS_CH_CTRL_EDSEL_DEFAULT << 24) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_OFF (_PRS_CH_CTRL_EDSEL_OFF << 24) /**< Shifted mode OFF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_POSEDGE (_PRS_CH_CTRL_EDSEL_POSEDGE << 24) /**< Shifted mode POSEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_NEGEDGE (_PRS_CH_CTRL_EDSEL_NEGEDGE << 24) /**< Shifted mode NEGEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_BOTHEDGES (_PRS_CH_CTRL_EDSEL_BOTHEDGES << 24) /**< Shifted mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC (0x1UL << 28) /**< Asynchronous reflex */
-#define _PRS_CH_CTRL_ASYNC_SHIFT 28 /**< Shift value for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_MASK 0x10000000UL /**< Bit mask for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC_DEFAULT (_PRS_CH_CTRL_ASYNC_DEFAULT << 28) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-
-/** @} End of group EFM32ZG108F16_PRS */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_UNLOCK EFM32ZG108F16 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG108F16_UNLOCK */
-
-/** @} End of group EFM32ZG108F16_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F16_Alternate_Function EFM32ZG108F16 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG108F16_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG108F16 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG108F16_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f32.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f32.h
deleted file mode 100644
index 6923dc425e..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f32.h
+++ /dev/null
@@ -1,2188 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG108F32
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG108F32_H
-#define EFM32ZG108F32_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32 EFM32ZG108F32
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_Core EFM32ZG108F32 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG108F32_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG108F32_Part EFM32ZG108F32 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG108F32)
-#define EFM32ZG108F32 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG108F32" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG108F32 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00008000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG108F32_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_Peripheral_TypeDefs EFM32ZG108F32 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_dma_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_DMA EFM32ZG108F32 DMA
- * @{
- * @brief EFM32ZG108F32_DMA Register Declaration
- ******************************************************************************/
-typedef struct {
- __IM uint32_t STATUS; /**< DMA Status Registers */
- __OM uint32_t CONFIG; /**< DMA Configuration Register */
- __IOM uint32_t CTRLBASE; /**< Channel Control Data Base Pointer Register */
- __IM uint32_t ALTCTRLBASE; /**< Channel Alternate Control Data Base Pointer Register */
- __IM uint32_t CHWAITSTATUS; /**< Channel Wait on Request Status Register */
- __OM uint32_t CHSWREQ; /**< Channel Software Request Register */
- __IOM uint32_t CHUSEBURSTS; /**< Channel Useburst Set Register */
- __OM uint32_t CHUSEBURSTC; /**< Channel Useburst Clear Register */
- __IOM uint32_t CHREQMASKS; /**< Channel Request Mask Set Register */
- __OM uint32_t CHREQMASKC; /**< Channel Request Mask Clear Register */
- __IOM uint32_t CHENS; /**< Channel Enable Set Register */
- __OM uint32_t CHENC; /**< Channel Enable Clear Register */
- __IOM uint32_t CHALTS; /**< Channel Alternate Set Register */
- __OM uint32_t CHALTC; /**< Channel Alternate Clear Register */
- __IOM uint32_t CHPRIS; /**< Channel Priority Set Register */
- __OM uint32_t CHPRIC; /**< Channel Priority Clear Register */
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t ERRORC; /**< Bus Error Clear Register */
-
- uint32_t RESERVED1[880U]; /**< Reserved for future use **/
- __IM uint32_t CHREQSTATUS; /**< Channel Request Status */
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IM uint32_t CHSREQSTATUS; /**< Channel Single Request Status */
-
- uint32_t RESERVED3[121U]; /**< Reserved for future use **/
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable register */
-
- uint32_t RESERVED4[60U]; /**< Reserved registers */
- DMA_CH_TypeDef CH[4U]; /**< Channel registers */
-} DMA_TypeDef; /** DMA Register Declaration *//** @} */
-
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_CMU EFM32ZG108F32 CMU
- * @{
- * @brief EFM32ZG108F32_CMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< CMU Control Register */
- __IOM uint32_t HFCORECLKDIV; /**< High Frequency Core Clock Division Register */
- __IOM uint32_t HFPERCLKDIV; /**< High Frequency Peripheral Clock Division Register */
- __IOM uint32_t HFRCOCTRL; /**< HFRCO Control Register */
- __IOM uint32_t LFRCOCTRL; /**< LFRCO Control Register */
- __IOM uint32_t AUXHFRCOCTRL; /**< AUXHFRCO Control Register */
- __IOM uint32_t CALCTRL; /**< Calibration Control Register */
- __IOM uint32_t CALCNT; /**< Calibration Counter Register */
- __IOM uint32_t OSCENCMD; /**< Oscillator Enable/Disable Command Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IOM uint32_t LFCLKSEL; /**< Low Frequency Clock Select Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t HFCORECLKEN0; /**< High Frequency Core Clock Enable Register 0 */
- __IOM uint32_t HFPERCLKEN0; /**< High Frequency Peripheral Clock Enable Register 0 */
- uint32_t RESERVED0[2U]; /**< Reserved for future use **/
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IOM uint32_t LFACLKEN0; /**< Low Frequency A Clock Enable Register 0 (Async Reg) */
- uint32_t RESERVED1[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBCLKEN0; /**< Low Frequency B Clock Enable Register 0 (Async Reg) */
-
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFAPRESC0; /**< Low Frequency A Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED3[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBPRESC0; /**< Low Frequency B Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED4[1U]; /**< Reserved for future use **/
- __IOM uint32_t PCNTCTRL; /**< PCNT Control Register */
-
- uint32_t RESERVED5[1U]; /**< Reserved for future use **/
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
-} CMU_TypeDef; /** CMU Register Declaration *//** @} */
-
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_PRS EFM32ZG108F32 PRS
- * @{
- * @brief EFM32ZG108F32_PRS Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t SWPULSE; /**< Software Pulse Register */
- __IOM uint32_t SWLEVEL; /**< Software Level Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved registers */
- PRS_CH_TypeDef CH[4U]; /**< Channel registers */
-} PRS_TypeDef; /** PRS Register Declaration *//** @} */
-
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG108F32_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_Peripheral_Base EFM32ZG108F32 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG108F32_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_Peripheral_Declaration EFM32ZG108F32 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG108F32_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_BitFields EFM32ZG108F32 Bit Fields
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @addtogroup EFM32ZG108F32_PRS_Signals
- * @{
- * @brief PRS Signal names
- ******************************************************************************/
-#define PRS_VCMP_OUT ((1 << 16) + 0) /**< PRS Voltage comparator output */
-#define PRS_ACMP0_OUT ((2 << 16) + 0) /**< PRS Analog comparator output */
-#define PRS_USART1_IRTX ((17 << 16) + 0) /**< PRS USART 1 IRDA out */
-#define PRS_USART1_TXC ((17 << 16) + 1) /**< PRS USART 1 TX complete */
-#define PRS_USART1_RXDATAV ((17 << 16) + 2) /**< PRS USART 1 RX Data Valid */
-#define PRS_TIMER0_UF ((28 << 16) + 0) /**< PRS Timer 0 Underflow */
-#define PRS_TIMER0_OF ((28 << 16) + 1) /**< PRS Timer 0 Overflow */
-#define PRS_TIMER0_CC0 ((28 << 16) + 2) /**< PRS Timer 0 Compare/Capture 0 */
-#define PRS_TIMER0_CC1 ((28 << 16) + 3) /**< PRS Timer 0 Compare/Capture 1 */
-#define PRS_TIMER0_CC2 ((28 << 16) + 4) /**< PRS Timer 0 Compare/Capture 2 */
-#define PRS_TIMER1_UF ((29 << 16) + 0) /**< PRS Timer 1 Underflow */
-#define PRS_TIMER1_OF ((29 << 16) + 1) /**< PRS Timer 1 Overflow */
-#define PRS_TIMER1_CC0 ((29 << 16) + 2) /**< PRS Timer 1 Compare/Capture 0 */
-#define PRS_TIMER1_CC1 ((29 << 16) + 3) /**< PRS Timer 1 Compare/Capture 1 */
-#define PRS_TIMER1_CC2 ((29 << 16) + 4) /**< PRS Timer 1 Compare/Capture 2 */
-#define PRS_RTC_OF ((40 << 16) + 0) /**< PRS RTC Overflow */
-#define PRS_RTC_COMP0 ((40 << 16) + 1) /**< PRS RTC Compare 0 */
-#define PRS_RTC_COMP1 ((40 << 16) + 2) /**< PRS RTC Compare 1 */
-#define PRS_GPIO_PIN0 ((48 << 16) + 0) /**< PRS GPIO pin 0 */
-#define PRS_GPIO_PIN1 ((48 << 16) + 1) /**< PRS GPIO pin 1 */
-#define PRS_GPIO_PIN2 ((48 << 16) + 2) /**< PRS GPIO pin 2 */
-#define PRS_GPIO_PIN3 ((48 << 16) + 3) /**< PRS GPIO pin 3 */
-#define PRS_GPIO_PIN4 ((48 << 16) + 4) /**< PRS GPIO pin 4 */
-#define PRS_GPIO_PIN5 ((48 << 16) + 5) /**< PRS GPIO pin 5 */
-#define PRS_GPIO_PIN6 ((48 << 16) + 6) /**< PRS GPIO pin 6 */
-#define PRS_GPIO_PIN7 ((48 << 16) + 7) /**< PRS GPIO pin 7 */
-#define PRS_GPIO_PIN8 ((49 << 16) + 0) /**< PRS GPIO pin 8 */
-#define PRS_GPIO_PIN9 ((49 << 16) + 1) /**< PRS GPIO pin 9 */
-#define PRS_GPIO_PIN10 ((49 << 16) + 2) /**< PRS GPIO pin 10 */
-#define PRS_GPIO_PIN11 ((49 << 16) + 3) /**< PRS GPIO pin 11 */
-#define PRS_GPIO_PIN12 ((49 << 16) + 4) /**< PRS GPIO pin 12 */
-#define PRS_GPIO_PIN13 ((49 << 16) + 5) /**< PRS GPIO pin 13 */
-#define PRS_GPIO_PIN14 ((49 << 16) + 6) /**< PRS GPIO pin 14 */
-#define PRS_GPIO_PIN15 ((49 << 16) + 7) /**< PRS GPIO pin 15 */
-#define PRS_PCNT0_TCC ((54 << 16) + 0) /**< PRS Triggered compare match */
-
-/** @} End of group EFM32ZG108F32_PRS */
-
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_DMA_BitFields EFM32ZG108F32_DMA Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for DMA STATUS */
-#define _DMA_STATUS_RESETVALUE 0x10030000UL /**< Default value for DMA_STATUS */
-#define _DMA_STATUS_MASK 0x001F00F1UL /**< Mask for DMA_STATUS */
-#define DMA_STATUS_EN (0x1UL << 0) /**< DMA Enable Status */
-#define _DMA_STATUS_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_STATUS_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_STATUS_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_EN_DEFAULT (_DMA_STATUS_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_SHIFT 4 /**< Shift value for DMA_STATE */
-#define _DMA_STATUS_STATE_MASK 0xF0UL /**< Bit mask for DMA_STATE */
-#define _DMA_STATUS_STATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_IDLE 0x00000000UL /**< Mode IDLE for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDCHCTRLDATA 0x00000001UL /**< Mode RDCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCENDPTR 0x00000002UL /**< Mode RDSRCENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDDSTENDPTR 0x00000003UL /**< Mode RDDSTENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCDATA 0x00000004UL /**< Mode RDSRCDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRDSTDATA 0x00000005UL /**< Mode WRDSTDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WAITREQCLR 0x00000006UL /**< Mode WAITREQCLR for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRCHCTRLDATA 0x00000007UL /**< Mode WRCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_STALLED 0x00000008UL /**< Mode STALLED for DMA_STATUS */
-#define _DMA_STATUS_STATE_DONE 0x00000009UL /**< Mode DONE for DMA_STATUS */
-#define _DMA_STATUS_STATE_PERSCATTRANS 0x0000000AUL /**< Mode PERSCATTRANS for DMA_STATUS */
-#define DMA_STATUS_STATE_DEFAULT (_DMA_STATUS_STATE_DEFAULT << 4) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_STATE_IDLE (_DMA_STATUS_STATE_IDLE << 4) /**< Shifted mode IDLE for DMA_STATUS */
-#define DMA_STATUS_STATE_RDCHCTRLDATA (_DMA_STATUS_STATE_RDCHCTRLDATA << 4) /**< Shifted mode RDCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCENDPTR (_DMA_STATUS_STATE_RDSRCENDPTR << 4) /**< Shifted mode RDSRCENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDDSTENDPTR (_DMA_STATUS_STATE_RDDSTENDPTR << 4) /**< Shifted mode RDDSTENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCDATA (_DMA_STATUS_STATE_RDSRCDATA << 4) /**< Shifted mode RDSRCDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WRDSTDATA (_DMA_STATUS_STATE_WRDSTDATA << 4) /**< Shifted mode WRDSTDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WAITREQCLR (_DMA_STATUS_STATE_WAITREQCLR << 4) /**< Shifted mode WAITREQCLR for DMA_STATUS */
-#define DMA_STATUS_STATE_WRCHCTRLDATA (_DMA_STATUS_STATE_WRCHCTRLDATA << 4) /**< Shifted mode WRCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_STALLED (_DMA_STATUS_STATE_STALLED << 4) /**< Shifted mode STALLED for DMA_STATUS */
-#define DMA_STATUS_STATE_DONE (_DMA_STATUS_STATE_DONE << 4) /**< Shifted mode DONE for DMA_STATUS */
-#define DMA_STATUS_STATE_PERSCATTRANS (_DMA_STATUS_STATE_PERSCATTRANS << 4) /**< Shifted mode PERSCATTRANS for DMA_STATUS */
-#define _DMA_STATUS_CHNUM_SHIFT 16 /**< Shift value for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_MASK 0x1F0000UL /**< Bit mask for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_DEFAULT 0x00000003UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_CHNUM_DEFAULT (_DMA_STATUS_CHNUM_DEFAULT << 16) /**< Shifted mode DEFAULT for DMA_STATUS */
-
-/* Bit fields for DMA CONFIG */
-#define _DMA_CONFIG_RESETVALUE 0x00000000UL /**< Default value for DMA_CONFIG */
-#define _DMA_CONFIG_MASK 0x00000021UL /**< Mask for DMA_CONFIG */
-#define DMA_CONFIG_EN (0x1UL << 0) /**< Enable DMA */
-#define _DMA_CONFIG_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_CONFIG_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_CONFIG_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_EN_DEFAULT (_DMA_CONFIG_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT (0x1UL << 5) /**< Channel Protection Control */
-#define _DMA_CONFIG_CHPROT_SHIFT 5 /**< Shift value for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_MASK 0x20UL /**< Bit mask for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT_DEFAULT (_DMA_CONFIG_CHPROT_DEFAULT << 5) /**< Shifted mode DEFAULT for DMA_CONFIG */
-
-/* Bit fields for DMA CTRLBASE */
-#define _DMA_CTRLBASE_RESETVALUE 0x00000000UL /**< Default value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_SHIFT 0 /**< Shift value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CTRLBASE */
-#define DMA_CTRLBASE_CTRLBASE_DEFAULT (_DMA_CTRLBASE_CTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CTRLBASE */
-
-/* Bit fields for DMA ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_RESETVALUE 0x00000040UL /**< Default value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_SHIFT 0 /**< Shift value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT 0x00000040UL /**< Mode DEFAULT for DMA_ALTCTRLBASE */
-#define DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT (_DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ALTCTRLBASE */
-
-/* Bit fields for DMA CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_RESETVALUE 0x0000000FUL /**< Default value for DMA_CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS (0x1UL << 0) /**< Channel 0 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_SHIFT 0 /**< Shift value for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS (0x1UL << 1) /**< Channel 1 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_SHIFT 1 /**< Shift value for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS (0x1UL << 2) /**< Channel 2 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_SHIFT 2 /**< Shift value for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS (0x1UL << 3) /**< Channel 3 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_SHIFT 3 /**< Shift value for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-
-/* Bit fields for DMA CHSWREQ */
-#define _DMA_CHSWREQ_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSWREQ */
-#define _DMA_CHSWREQ_MASK 0x0000000FUL /**< Mask for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ (0x1UL << 0) /**< Channel 0 Software Request */
-#define _DMA_CHSWREQ_CH0SWREQ_SHIFT 0 /**< Shift value for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_MASK 0x1UL /**< Bit mask for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ_DEFAULT (_DMA_CHSWREQ_CH0SWREQ_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ (0x1UL << 1) /**< Channel 1 Software Request */
-#define _DMA_CHSWREQ_CH1SWREQ_SHIFT 1 /**< Shift value for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_MASK 0x2UL /**< Bit mask for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ_DEFAULT (_DMA_CHSWREQ_CH1SWREQ_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ (0x1UL << 2) /**< Channel 2 Software Request */
-#define _DMA_CHSWREQ_CH2SWREQ_SHIFT 2 /**< Shift value for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_MASK 0x4UL /**< Bit mask for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ_DEFAULT (_DMA_CHSWREQ_CH2SWREQ_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ (0x1UL << 3) /**< Channel 3 Software Request */
-#define _DMA_CHSWREQ_CH3SWREQ_SHIFT 3 /**< Shift value for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_MASK 0x8UL /**< Bit mask for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ_DEFAULT (_DMA_CHSWREQ_CH3SWREQ_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-
-/* Bit fields for DMA CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS (0x1UL << 0) /**< Channel 0 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST 0x00000000UL /**< Mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY 0x00000001UL /**< Mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST (_DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST << 0) /**< Shifted mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY (_DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY << 0) /**< Shifted mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS (0x1UL << 1) /**< Channel 1 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS (0x1UL << 2) /**< Channel 2 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS (0x1UL << 3) /**< Channel 3 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-
-/* Bit fields for DMA CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC (0x1UL << 0) /**< Channel 0 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC (0x1UL << 1) /**< Channel 1 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC (0x1UL << 2) /**< Channel 2 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC (0x1UL << 3) /**< Channel 3 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-
-/* Bit fields for DMA CHREQMASKS */
-#define _DMA_CHREQMASKS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKS */
-#define _DMA_CHREQMASKS_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS (0x1UL << 0) /**< Channel 0 Request Mask Set */
-#define _DMA_CHREQMASKS_CH0REQMASKS_SHIFT 0 /**< Shift value for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH0REQMASKS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS (0x1UL << 1) /**< Channel 1 Request Mask Set */
-#define _DMA_CHREQMASKS_CH1REQMASKS_SHIFT 1 /**< Shift value for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH1REQMASKS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS (0x1UL << 2) /**< Channel 2 Request Mask Set */
-#define _DMA_CHREQMASKS_CH2REQMASKS_SHIFT 2 /**< Shift value for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH2REQMASKS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS (0x1UL << 3) /**< Channel 3 Request Mask Set */
-#define _DMA_CHREQMASKS_CH3REQMASKS_SHIFT 3 /**< Shift value for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH3REQMASKS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-
-/* Bit fields for DMA CHREQMASKC */
-#define _DMA_CHREQMASKC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKC */
-#define _DMA_CHREQMASKC_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC (0x1UL << 0) /**< Channel 0 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH0REQMASKC_SHIFT 0 /**< Shift value for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH0REQMASKC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC (0x1UL << 1) /**< Channel 1 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH1REQMASKC_SHIFT 1 /**< Shift value for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH1REQMASKC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC (0x1UL << 2) /**< Channel 2 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH2REQMASKC_SHIFT 2 /**< Shift value for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH2REQMASKC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC (0x1UL << 3) /**< Channel 3 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH3REQMASKC_SHIFT 3 /**< Shift value for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH3REQMASKC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-
-/* Bit fields for DMA CHENS */
-#define _DMA_CHENS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENS */
-#define _DMA_CHENS_MASK 0x0000000FUL /**< Mask for DMA_CHENS */
-#define DMA_CHENS_CH0ENS (0x1UL << 0) /**< Channel 0 Enable Set */
-#define _DMA_CHENS_CH0ENS_SHIFT 0 /**< Shift value for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_MASK 0x1UL /**< Bit mask for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH0ENS_DEFAULT (_DMA_CHENS_CH0ENS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS (0x1UL << 1) /**< Channel 1 Enable Set */
-#define _DMA_CHENS_CH1ENS_SHIFT 1 /**< Shift value for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_MASK 0x2UL /**< Bit mask for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS_DEFAULT (_DMA_CHENS_CH1ENS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS (0x1UL << 2) /**< Channel 2 Enable Set */
-#define _DMA_CHENS_CH2ENS_SHIFT 2 /**< Shift value for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_MASK 0x4UL /**< Bit mask for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS_DEFAULT (_DMA_CHENS_CH2ENS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS (0x1UL << 3) /**< Channel 3 Enable Set */
-#define _DMA_CHENS_CH3ENS_SHIFT 3 /**< Shift value for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_MASK 0x8UL /**< Bit mask for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS_DEFAULT (_DMA_CHENS_CH3ENS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENS */
-
-/* Bit fields for DMA CHENC */
-#define _DMA_CHENC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENC */
-#define _DMA_CHENC_MASK 0x0000000FUL /**< Mask for DMA_CHENC */
-#define DMA_CHENC_CH0ENC (0x1UL << 0) /**< Channel 0 Enable Clear */
-#define _DMA_CHENC_CH0ENC_SHIFT 0 /**< Shift value for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_MASK 0x1UL /**< Bit mask for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH0ENC_DEFAULT (_DMA_CHENC_CH0ENC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC (0x1UL << 1) /**< Channel 1 Enable Clear */
-#define _DMA_CHENC_CH1ENC_SHIFT 1 /**< Shift value for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_MASK 0x2UL /**< Bit mask for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC_DEFAULT (_DMA_CHENC_CH1ENC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC (0x1UL << 2) /**< Channel 2 Enable Clear */
-#define _DMA_CHENC_CH2ENC_SHIFT 2 /**< Shift value for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_MASK 0x4UL /**< Bit mask for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC_DEFAULT (_DMA_CHENC_CH2ENC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC (0x1UL << 3) /**< Channel 3 Enable Clear */
-#define _DMA_CHENC_CH3ENC_SHIFT 3 /**< Shift value for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_MASK 0x8UL /**< Bit mask for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC_DEFAULT (_DMA_CHENC_CH3ENC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENC */
-
-/* Bit fields for DMA CHALTS */
-#define _DMA_CHALTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTS */
-#define _DMA_CHALTS_MASK 0x0000000FUL /**< Mask for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS (0x1UL << 0) /**< Channel 0 Alternate Structure Set */
-#define _DMA_CHALTS_CH0ALTS_SHIFT 0 /**< Shift value for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_MASK 0x1UL /**< Bit mask for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS_DEFAULT (_DMA_CHALTS_CH0ALTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS (0x1UL << 1) /**< Channel 1 Alternate Structure Set */
-#define _DMA_CHALTS_CH1ALTS_SHIFT 1 /**< Shift value for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_MASK 0x2UL /**< Bit mask for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS_DEFAULT (_DMA_CHALTS_CH1ALTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS (0x1UL << 2) /**< Channel 2 Alternate Structure Set */
-#define _DMA_CHALTS_CH2ALTS_SHIFT 2 /**< Shift value for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_MASK 0x4UL /**< Bit mask for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS_DEFAULT (_DMA_CHALTS_CH2ALTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS (0x1UL << 3) /**< Channel 3 Alternate Structure Set */
-#define _DMA_CHALTS_CH3ALTS_SHIFT 3 /**< Shift value for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_MASK 0x8UL /**< Bit mask for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS_DEFAULT (_DMA_CHALTS_CH3ALTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTS */
-
-/* Bit fields for DMA CHALTC */
-#define _DMA_CHALTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTC */
-#define _DMA_CHALTC_MASK 0x0000000FUL /**< Mask for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC (0x1UL << 0) /**< Channel 0 Alternate Clear */
-#define _DMA_CHALTC_CH0ALTC_SHIFT 0 /**< Shift value for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_MASK 0x1UL /**< Bit mask for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC_DEFAULT (_DMA_CHALTC_CH0ALTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC (0x1UL << 1) /**< Channel 1 Alternate Clear */
-#define _DMA_CHALTC_CH1ALTC_SHIFT 1 /**< Shift value for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_MASK 0x2UL /**< Bit mask for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC_DEFAULT (_DMA_CHALTC_CH1ALTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC (0x1UL << 2) /**< Channel 2 Alternate Clear */
-#define _DMA_CHALTC_CH2ALTC_SHIFT 2 /**< Shift value for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_MASK 0x4UL /**< Bit mask for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC_DEFAULT (_DMA_CHALTC_CH2ALTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC (0x1UL << 3) /**< Channel 3 Alternate Clear */
-#define _DMA_CHALTC_CH3ALTC_SHIFT 3 /**< Shift value for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_MASK 0x8UL /**< Bit mask for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC_DEFAULT (_DMA_CHALTC_CH3ALTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTC */
-
-/* Bit fields for DMA CHPRIS */
-#define _DMA_CHPRIS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIS */
-#define _DMA_CHPRIS_MASK 0x0000000FUL /**< Mask for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS (0x1UL << 0) /**< Channel 0 High Priority Set */
-#define _DMA_CHPRIS_CH0PRIS_SHIFT 0 /**< Shift value for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_MASK 0x1UL /**< Bit mask for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS_DEFAULT (_DMA_CHPRIS_CH0PRIS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS (0x1UL << 1) /**< Channel 1 High Priority Set */
-#define _DMA_CHPRIS_CH1PRIS_SHIFT 1 /**< Shift value for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_MASK 0x2UL /**< Bit mask for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS_DEFAULT (_DMA_CHPRIS_CH1PRIS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS (0x1UL << 2) /**< Channel 2 High Priority Set */
-#define _DMA_CHPRIS_CH2PRIS_SHIFT 2 /**< Shift value for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_MASK 0x4UL /**< Bit mask for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS_DEFAULT (_DMA_CHPRIS_CH2PRIS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS (0x1UL << 3) /**< Channel 3 High Priority Set */
-#define _DMA_CHPRIS_CH3PRIS_SHIFT 3 /**< Shift value for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_MASK 0x8UL /**< Bit mask for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS_DEFAULT (_DMA_CHPRIS_CH3PRIS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-
-/* Bit fields for DMA CHPRIC */
-#define _DMA_CHPRIC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIC */
-#define _DMA_CHPRIC_MASK 0x0000000FUL /**< Mask for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC (0x1UL << 0) /**< Channel 0 High Priority Clear */
-#define _DMA_CHPRIC_CH0PRIC_SHIFT 0 /**< Shift value for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_MASK 0x1UL /**< Bit mask for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC_DEFAULT (_DMA_CHPRIC_CH0PRIC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC (0x1UL << 1) /**< Channel 1 High Priority Clear */
-#define _DMA_CHPRIC_CH1PRIC_SHIFT 1 /**< Shift value for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_MASK 0x2UL /**< Bit mask for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC_DEFAULT (_DMA_CHPRIC_CH1PRIC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC (0x1UL << 2) /**< Channel 2 High Priority Clear */
-#define _DMA_CHPRIC_CH2PRIC_SHIFT 2 /**< Shift value for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_MASK 0x4UL /**< Bit mask for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC_DEFAULT (_DMA_CHPRIC_CH2PRIC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC (0x1UL << 3) /**< Channel 3 High Priority Clear */
-#define _DMA_CHPRIC_CH3PRIC_SHIFT 3 /**< Shift value for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_MASK 0x8UL /**< Bit mask for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC_DEFAULT (_DMA_CHPRIC_CH3PRIC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-
-/* Bit fields for DMA ERRORC */
-#define _DMA_ERRORC_RESETVALUE 0x00000000UL /**< Default value for DMA_ERRORC */
-#define _DMA_ERRORC_MASK 0x00000001UL /**< Mask for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC (0x1UL << 0) /**< Bus Error Clear */
-#define _DMA_ERRORC_ERRORC_SHIFT 0 /**< Shift value for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_MASK 0x1UL /**< Bit mask for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC_DEFAULT (_DMA_ERRORC_ERRORC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ERRORC */
-
-/* Bit fields for DMA CHREQSTATUS */
-#define _DMA_CHREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQSTATUS */
-#define _DMA_CHREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS (0x1UL << 0) /**< Channel 0 Request Status */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS (0x1UL << 1) /**< Channel 1 Request Status */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS (0x1UL << 2) /**< Channel 2 Request Status */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS (0x1UL << 3) /**< Channel 3 Request Status */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-
-/* Bit fields for DMA CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS (0x1UL << 0) /**< Channel 0 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS (0x1UL << 1) /**< Channel 1 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS (0x1UL << 2) /**< Channel 2 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS (0x1UL << 3) /**< Channel 3 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-
-/* Bit fields for DMA IF */
-#define _DMA_IF_RESETVALUE 0x00000000UL /**< Default value for DMA_IF */
-#define _DMA_IF_MASK 0x8000000FUL /**< Mask for DMA_IF */
-#define DMA_IF_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag */
-#define _DMA_IF_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH0DONE_DEFAULT (_DMA_IF_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag */
-#define _DMA_IF_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE_DEFAULT (_DMA_IF_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag */
-#define _DMA_IF_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE_DEFAULT (_DMA_IF_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag */
-#define _DMA_IF_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE_DEFAULT (_DMA_IF_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag */
-#define _DMA_IF_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IF_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IF_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR_DEFAULT (_DMA_IF_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IF */
-
-/* Bit fields for DMA IFS */
-#define _DMA_IFS_RESETVALUE 0x00000000UL /**< Default value for DMA_IFS */
-#define _DMA_IFS_MASK 0x8000000FUL /**< Mask for DMA_IFS */
-#define DMA_IFS_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH0DONE_DEFAULT (_DMA_IFS_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE_DEFAULT (_DMA_IFS_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE_DEFAULT (_DMA_IFS_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE_DEFAULT (_DMA_IFS_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Set */
-#define _DMA_IFS_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFS_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFS_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR_DEFAULT (_DMA_IFS_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFS */
-
-/* Bit fields for DMA IFC */
-#define _DMA_IFC_RESETVALUE 0x00000000UL /**< Default value for DMA_IFC */
-#define _DMA_IFC_MASK 0x8000000FUL /**< Mask for DMA_IFC */
-#define DMA_IFC_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH0DONE_DEFAULT (_DMA_IFC_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE_DEFAULT (_DMA_IFC_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE_DEFAULT (_DMA_IFC_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE_DEFAULT (_DMA_IFC_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Clear */
-#define _DMA_IFC_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFC_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFC_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR_DEFAULT (_DMA_IFC_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFC */
-
-/* Bit fields for DMA IEN */
-#define _DMA_IEN_RESETVALUE 0x00000000UL /**< Default value for DMA_IEN */
-#define _DMA_IEN_MASK 0x8000000FUL /**< Mask for DMA_IEN */
-#define DMA_IEN_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Enable */
-#define _DMA_IEN_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH0DONE_DEFAULT (_DMA_IEN_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Enable */
-#define _DMA_IEN_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE_DEFAULT (_DMA_IEN_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Enable */
-#define _DMA_IEN_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE_DEFAULT (_DMA_IEN_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Enable */
-#define _DMA_IEN_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE_DEFAULT (_DMA_IEN_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Enable */
-#define _DMA_IEN_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IEN_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IEN_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR_DEFAULT (_DMA_IEN_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IEN */
-
-/* Bit fields for DMA CH_CTRL */
-#define _DMA_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_MASK 0x003F000FUL /**< Mask for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_MASK 0xFUL /**< Bit mask for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000000UL /**< Mode USART1RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV 0x00000000UL /**< Mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0RXDATAV 0x00000000UL /**< Mode I2C0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0UFOF 0x00000000UL /**< Mode TIMER0UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1UFOF 0x00000000UL /**< Mode TIMER1UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_MSCWDATA 0x00000000UL /**< Mode MSCWDATA for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBL 0x00000001UL /**< Mode USART1TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXBL 0x00000001UL /**< Mode LEUART0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0TXBL 0x00000001UL /**< Mode I2C0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC0 0x00000001UL /**< Mode TIMER0CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC0 0x00000001UL /**< Mode TIMER1CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXEMPTY 0x00000002UL /**< Mode USART1TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY 0x00000002UL /**< Mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC1 0x00000002UL /**< Mode TIMER0CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC1 0x00000002UL /**< Mode TIMER1CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT 0x00000003UL /**< Mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC2 0x00000003UL /**< Mode TIMER0CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC2 0x00000003UL /**< Mode TIMER1CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT 0x00000004UL /**< Mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAV (_DMA_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV (_DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV << 0) /**< Shifted mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0RXDATAV (_DMA_CH_CTRL_SIGSEL_I2C0RXDATAV << 0) /**< Shifted mode I2C0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0UFOF (_DMA_CH_CTRL_SIGSEL_TIMER0UFOF << 0) /**< Shifted mode TIMER0UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1UFOF (_DMA_CH_CTRL_SIGSEL_TIMER1UFOF << 0) /**< Shifted mode TIMER1UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_MSCWDATA (_DMA_CH_CTRL_SIGSEL_MSCWDATA << 0) /**< Shifted mode MSCWDATA for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBL (_DMA_CH_CTRL_SIGSEL_USART1TXBL << 0) /**< Shifted mode USART1TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXBL (_DMA_CH_CTRL_SIGSEL_LEUART0TXBL << 0) /**< Shifted mode LEUART0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0TXBL (_DMA_CH_CTRL_SIGSEL_I2C0TXBL << 0) /**< Shifted mode I2C0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC0 (_DMA_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC0 (_DMA_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXEMPTY (_DMA_CH_CTRL_SIGSEL_USART1TXEMPTY << 0) /**< Shifted mode USART1TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY (_DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY << 0) /**< Shifted mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC1 (_DMA_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC1 (_DMA_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT (_DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT << 0) /**< Shifted mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC2 (_DMA_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC2 (_DMA_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT (_DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT << 0) /**< Shifted mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_USART1 0x0000000DUL /**< Mode USART1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_LEUART0 0x00000010UL /**< Mode LEUART0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_I2C0 0x00000014UL /**< Mode I2C0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER0 0x00000018UL /**< Mode TIMER0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER1 0x00000019UL /**< Mode TIMER1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_MSC 0x00000030UL /**< Mode MSC for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_NONE (_DMA_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_USART1 (_DMA_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_LEUART0 (_DMA_CH_CTRL_SOURCESEL_LEUART0 << 16) /**< Shifted mode LEUART0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_I2C0 (_DMA_CH_CTRL_SOURCESEL_I2C0 << 16) /**< Shifted mode I2C0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER0 (_DMA_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER1 (_DMA_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_MSC (_DMA_CH_CTRL_SOURCESEL_MSC << 16) /**< Shifted mode MSC for DMA_CH_CTRL */
-
-/** @} End of group EFM32ZG108F32_DMA */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_CMU_BitFields EFM32ZG108F32_CMU Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for CMU CTRL */
-#define _CMU_CTRL_RESETVALUE 0x000C262CUL /**< Default value for CMU_CTRL */
-#define _CMU_CTRL_MASK 0x07FE3EEFUL /**< Mask for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_SHIFT 0 /**< Shift value for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_MASK 0x3UL /**< Bit mask for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DEFAULT (_CMU_CTRL_HFXOMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_XTAL (_CMU_CTRL_HFXOMODE_XTAL << 0) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_BUFEXTCLK (_CMU_CTRL_HFXOMODE_BUFEXTCLK << 0) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DIGEXTCLK (_CMU_CTRL_HFXOMODE_DIGEXTCLK << 0) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_SHIFT 2 /**< Shift value for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_MASK 0xCUL /**< Bit mask for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_50PCENT 0x00000000UL /**< Mode 50PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_70PCENT 0x00000001UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_80PCENT 0x00000002UL /**< Mode 80PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_100PCENT 0x00000003UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_50PCENT (_CMU_CTRL_HFXOBOOST_50PCENT << 2) /**< Shifted mode 50PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_70PCENT (_CMU_CTRL_HFXOBOOST_70PCENT << 2) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_80PCENT (_CMU_CTRL_HFXOBOOST_80PCENT << 2) /**< Shifted mode 80PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_DEFAULT (_CMU_CTRL_HFXOBOOST_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_100PCENT (_CMU_CTRL_HFXOBOOST_100PCENT << 2) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBUFCUR_SHIFT 5 /**< Shift value for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_MASK 0x60UL /**< Bit mask for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBUFCUR_DEFAULT (_CMU_CTRL_HFXOBUFCUR_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN (0x1UL << 7) /**< HFXO Glitch Detector Enable */
-#define _CMU_CTRL_HFXOGLITCHDETEN_SHIFT 7 /**< Shift value for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_MASK 0x80UL /**< Bit mask for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN_DEFAULT (_CMU_CTRL_HFXOGLITCHDETEN_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_SHIFT 9 /**< Shift value for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_MASK 0x600UL /**< Bit mask for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_256CYCLES 0x00000001UL /**< Mode 256CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_1KCYCLES 0x00000002UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_16KCYCLES 0x00000003UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_8CYCLES (_CMU_CTRL_HFXOTIMEOUT_8CYCLES << 9) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_256CYCLES (_CMU_CTRL_HFXOTIMEOUT_256CYCLES << 9) /**< Shifted mode 256CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_1KCYCLES (_CMU_CTRL_HFXOTIMEOUT_1KCYCLES << 9) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_DEFAULT (_CMU_CTRL_HFXOTIMEOUT_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_16KCYCLES (_CMU_CTRL_HFXOTIMEOUT_16KCYCLES << 9) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_SHIFT 11 /**< Shift value for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_MASK 0x1800UL /**< Bit mask for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DEFAULT (_CMU_CTRL_LFXOMODE_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_XTAL (_CMU_CTRL_LFXOMODE_XTAL << 11) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_BUFEXTCLK (_CMU_CTRL_LFXOMODE_BUFEXTCLK << 11) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DIGEXTCLK (_CMU_CTRL_LFXOMODE_DIGEXTCLK << 11) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST (0x1UL << 13) /**< LFXO Start-up Boost Current */
-#define _CMU_CTRL_LFXOBOOST_SHIFT 13 /**< Shift value for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_MASK 0x2000UL /**< Bit mask for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_70PCENT 0x00000000UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_100PCENT 0x00000001UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_70PCENT (_CMU_CTRL_LFXOBOOST_70PCENT << 13) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_DEFAULT (_CMU_CTRL_LFXOBOOST_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_100PCENT (_CMU_CTRL_LFXOBOOST_100PCENT << 13) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR (0x1UL << 17) /**< LFXO Boost Buffer Current */
-#define _CMU_CTRL_LFXOBUFCUR_SHIFT 17 /**< Shift value for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_MASK 0x20000UL /**< Bit mask for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR_DEFAULT (_CMU_CTRL_LFXOBUFCUR_DEFAULT << 17) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_SHIFT 18 /**< Shift value for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_MASK 0xC0000UL /**< Bit mask for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_1KCYCLES 0x00000001UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_16KCYCLES 0x00000002UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_32KCYCLES 0x00000003UL /**< Mode 32KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_8CYCLES (_CMU_CTRL_LFXOTIMEOUT_8CYCLES << 18) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_1KCYCLES (_CMU_CTRL_LFXOTIMEOUT_1KCYCLES << 18) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_16KCYCLES (_CMU_CTRL_LFXOTIMEOUT_16KCYCLES << 18) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_DEFAULT (_CMU_CTRL_LFXOTIMEOUT_DEFAULT << 18) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_32KCYCLES (_CMU_CTRL_LFXOTIMEOUT_32KCYCLES << 18) /**< Shifted mode 32KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_SHIFT 20 /**< Shift value for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_MASK 0x700000UL /**< Bit mask for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFRCO 0x00000000UL /**< Mode HFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFXO 0x00000001UL /**< Mode HFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK2 0x00000002UL /**< Mode HFCLK2 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK4 0x00000003UL /**< Mode HFCLK4 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK8 0x00000004UL /**< Mode HFCLK8 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK16 0x00000005UL /**< Mode HFCLK16 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_ULFRCO 0x00000006UL /**< Mode ULFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_AUXHFRCO 0x00000007UL /**< Mode AUXHFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_DEFAULT (_CMU_CTRL_CLKOUTSEL0_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFRCO (_CMU_CTRL_CLKOUTSEL0_HFRCO << 20) /**< Shifted mode HFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFXO (_CMU_CTRL_CLKOUTSEL0_HFXO << 20) /**< Shifted mode HFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK2 (_CMU_CTRL_CLKOUTSEL0_HFCLK2 << 20) /**< Shifted mode HFCLK2 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK4 (_CMU_CTRL_CLKOUTSEL0_HFCLK4 << 20) /**< Shifted mode HFCLK4 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK8 (_CMU_CTRL_CLKOUTSEL0_HFCLK8 << 20) /**< Shifted mode HFCLK8 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK16 (_CMU_CTRL_CLKOUTSEL0_HFCLK16 << 20) /**< Shifted mode HFCLK16 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_ULFRCO (_CMU_CTRL_CLKOUTSEL0_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_AUXHFRCO (_CMU_CTRL_CLKOUTSEL0_AUXHFRCO << 20) /**< Shifted mode AUXHFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_SHIFT 23 /**< Shift value for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_MASK 0x7800000UL /**< Bit mask for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCO 0x00000000UL /**< Mode LFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXO 0x00000001UL /**< Mode LFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFCLK 0x00000002UL /**< Mode HFCLK for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXOQ 0x00000003UL /**< Mode LFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFXOQ 0x00000004UL /**< Mode HFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCOQ 0x00000005UL /**< Mode LFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFRCOQ 0x00000006UL /**< Mode HFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ 0x00000007UL /**< Mode AUXHFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_DEFAULT (_CMU_CTRL_CLKOUTSEL1_DEFAULT << 23) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCO (_CMU_CTRL_CLKOUTSEL1_LFRCO << 23) /**< Shifted mode LFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXO (_CMU_CTRL_CLKOUTSEL1_LFXO << 23) /**< Shifted mode LFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFCLK (_CMU_CTRL_CLKOUTSEL1_HFCLK << 23) /**< Shifted mode HFCLK for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXOQ (_CMU_CTRL_CLKOUTSEL1_LFXOQ << 23) /**< Shifted mode LFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFXOQ (_CMU_CTRL_CLKOUTSEL1_HFXOQ << 23) /**< Shifted mode HFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCOQ (_CMU_CTRL_CLKOUTSEL1_LFRCOQ << 23) /**< Shifted mode LFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFRCOQ (_CMU_CTRL_CLKOUTSEL1_HFRCOQ << 23) /**< Shifted mode HFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ (_CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ << 23) /**< Shifted mode AUXHFRCOQ for CMU_CTRL */
-
-/* Bit fields for CMU HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_SHIFT 0 /**< Shift value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV (0x1UL << 8) /**< Additional Division Factor For HFCORECLKLE */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_SHIFT 8 /**< Shift value for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_MASK 0x100UL /**< Bit mask for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 0x00000000UL /**< Mode DIV2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 0x00000001UL /**< Mode DIV4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 << 8) /**< Shifted mode DIV2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 << 8) /**< Shifted mode DIV4 for CMU_HFCORECLKDIV */
-
-/* Bit fields for CMU HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_RESETVALUE 0x00000100UL /**< Default value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_SHIFT 0 /**< Shift value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN (0x1UL << 8) /**< HFPERCLK Enable */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_SHIFT 8 /**< Shift value for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_MASK 0x100UL /**< Bit mask for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-
-/* Bit fields for CMU HFRCOCTRL */
-#define _CMU_HFRCOCTRL_RESETVALUE 0x00000380UL /**< Default value for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_MASK 0x0001F7FFUL /**< Mask for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_TUNING_DEFAULT (_CMU_HFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_1MHZ 0x00000000UL /**< Mode 1MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_7MHZ 0x00000001UL /**< Mode 7MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_11MHZ 0x00000002UL /**< Mode 11MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_14MHZ 0x00000003UL /**< Mode 14MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_21MHZ 0x00000004UL /**< Mode 21MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_1MHZ (_CMU_HFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_7MHZ (_CMU_HFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_11MHZ (_CMU_HFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_DEFAULT (_CMU_HFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_14MHZ (_CMU_HFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_21MHZ (_CMU_HFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_SUDELAY_SHIFT 12 /**< Shift value for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_MASK 0x1F000UL /**< Bit mask for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_SUDELAY_DEFAULT (_CMU_HFRCOCTRL_SUDELAY_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-
-/* Bit fields for CMU LFRCOCTRL */
-#define _CMU_LFRCOCTRL_RESETVALUE 0x00000040UL /**< Default value for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_MASK 0x0000007FUL /**< Mask for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_MASK 0x7FUL /**< Bit mask for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_DEFAULT 0x00000040UL /**< Mode DEFAULT for CMU_LFRCOCTRL */
-#define CMU_LFRCOCTRL_TUNING_DEFAULT (_CMU_LFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFRCOCTRL */
-
-/* Bit fields for CMU AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_RESETVALUE 0x00000080UL /**< Default value for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_MASK 0x000007FFUL /**< Mask for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_TUNING_DEFAULT (_CMU_AUXHFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_14MHZ 0x00000000UL /**< Mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_11MHZ 0x00000001UL /**< Mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_7MHZ 0x00000002UL /**< Mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_1MHZ 0x00000003UL /**< Mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_21MHZ 0x00000007UL /**< Mode 21MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_DEFAULT (_CMU_AUXHFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_14MHZ (_CMU_AUXHFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_11MHZ (_CMU_AUXHFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_7MHZ (_CMU_AUXHFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_1MHZ (_CMU_AUXHFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_21MHZ (_CMU_AUXHFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_AUXHFRCOCTRL */
-
-/* Bit fields for CMU CALCTRL */
-#define _CMU_CALCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCTRL */
-#define _CMU_CALCTRL_MASK 0x0000007FUL /**< Mask for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_SHIFT 0 /**< Shift value for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_MASK 0x7UL /**< Bit mask for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFXO 0x00000000UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFXO 0x00000001UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFRCO 0x00000002UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_AUXHFRCO 0x00000004UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_DEFAULT (_CMU_CALCTRL_UPSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFXO (_CMU_CALCTRL_UPSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFXO (_CMU_CALCTRL_UPSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFRCO (_CMU_CALCTRL_UPSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFRCO (_CMU_CALCTRL_UPSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_AUXHFRCO (_CMU_CALCTRL_UPSEL_AUXHFRCO << 0) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_SHIFT 3 /**< Shift value for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_MASK 0x38UL /**< Bit mask for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFXO 0x00000001UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFXO 0x00000002UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFRCO 0x00000003UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFRCO 0x00000004UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_AUXHFRCO 0x00000005UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_DEFAULT (_CMU_CALCTRL_DOWNSEL_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFCLK (_CMU_CALCTRL_DOWNSEL_HFCLK << 3) /**< Shifted mode HFCLK for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFXO (_CMU_CALCTRL_DOWNSEL_HFXO << 3) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFXO (_CMU_CALCTRL_DOWNSEL_LFXO << 3) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFRCO (_CMU_CALCTRL_DOWNSEL_HFRCO << 3) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFRCO (_CMU_CALCTRL_DOWNSEL_LFRCO << 3) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_AUXHFRCO (_CMU_CALCTRL_DOWNSEL_AUXHFRCO << 3) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT (0x1UL << 6) /**< Continuous Calibration */
-#define _CMU_CALCTRL_CONT_SHIFT 6 /**< Shift value for CMU_CONT */
-#define _CMU_CALCTRL_CONT_MASK 0x40UL /**< Bit mask for CMU_CONT */
-#define _CMU_CALCTRL_CONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT_DEFAULT (_CMU_CALCTRL_CONT_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-
-/* Bit fields for CMU CALCNT */
-#define _CMU_CALCNT_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCNT */
-#define _CMU_CALCNT_MASK 0x000FFFFFUL /**< Mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_SHIFT 0 /**< Shift value for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_MASK 0xFFFFFUL /**< Bit mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCNT */
-#define CMU_CALCNT_CALCNT_DEFAULT (_CMU_CALCNT_CALCNT_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCNT */
-
-/* Bit fields for CMU OSCENCMD */
-#define _CMU_OSCENCMD_RESETVALUE 0x00000000UL /**< Default value for CMU_OSCENCMD */
-#define _CMU_OSCENCMD_MASK 0x000003FFUL /**< Mask for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN (0x1UL << 0) /**< HFRCO Enable */
-#define _CMU_OSCENCMD_HFRCOEN_SHIFT 0 /**< Shift value for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_MASK 0x1UL /**< Bit mask for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN_DEFAULT (_CMU_OSCENCMD_HFRCOEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS (0x1UL << 1) /**< HFRCO Disable */
-#define _CMU_OSCENCMD_HFRCODIS_SHIFT 1 /**< Shift value for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_MASK 0x2UL /**< Bit mask for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS_DEFAULT (_CMU_OSCENCMD_HFRCODIS_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN (0x1UL << 2) /**< HFXO Enable */
-#define _CMU_OSCENCMD_HFXOEN_SHIFT 2 /**< Shift value for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_MASK 0x4UL /**< Bit mask for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN_DEFAULT (_CMU_OSCENCMD_HFXOEN_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS (0x1UL << 3) /**< HFXO Disable */
-#define _CMU_OSCENCMD_HFXODIS_SHIFT 3 /**< Shift value for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_MASK 0x8UL /**< Bit mask for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS_DEFAULT (_CMU_OSCENCMD_HFXODIS_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN (0x1UL << 4) /**< AUXHFRCO Enable */
-#define _CMU_OSCENCMD_AUXHFRCOEN_SHIFT 4 /**< Shift value for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN_DEFAULT (_CMU_OSCENCMD_AUXHFRCOEN_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS (0x1UL << 5) /**< AUXHFRCO Disable */
-#define _CMU_OSCENCMD_AUXHFRCODIS_SHIFT 5 /**< Shift value for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS_DEFAULT (_CMU_OSCENCMD_AUXHFRCODIS_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN (0x1UL << 6) /**< LFRCO Enable */
-#define _CMU_OSCENCMD_LFRCOEN_SHIFT 6 /**< Shift value for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_MASK 0x40UL /**< Bit mask for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN_DEFAULT (_CMU_OSCENCMD_LFRCOEN_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS (0x1UL << 7) /**< LFRCO Disable */
-#define _CMU_OSCENCMD_LFRCODIS_SHIFT 7 /**< Shift value for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_MASK 0x80UL /**< Bit mask for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS_DEFAULT (_CMU_OSCENCMD_LFRCODIS_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN (0x1UL << 8) /**< LFXO Enable */
-#define _CMU_OSCENCMD_LFXOEN_SHIFT 8 /**< Shift value for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_MASK 0x100UL /**< Bit mask for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN_DEFAULT (_CMU_OSCENCMD_LFXOEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS (0x1UL << 9) /**< LFXO Disable */
-#define _CMU_OSCENCMD_LFXODIS_SHIFT 9 /**< Shift value for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_MASK 0x200UL /**< Bit mask for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS_DEFAULT (_CMU_OSCENCMD_LFXODIS_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-
-/* Bit fields for CMU CMD */
-#define _CMU_CMD_RESETVALUE 0x00000000UL /**< Default value for CMU_CMD */
-#define _CMU_CMD_MASK 0x0000001FUL /**< Mask for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_SHIFT 0 /**< Shift value for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_MASK 0x7UL /**< Bit mask for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFRCO 0x00000001UL /**< Mode HFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFXO 0x00000002UL /**< Mode HFXO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFXO 0x00000004UL /**< Mode LFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_DEFAULT (_CMU_CMD_HFCLKSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFRCO (_CMU_CMD_HFCLKSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFXO (_CMU_CMD_HFCLKSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFRCO (_CMU_CMD_HFCLKSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFXO (_CMU_CMD_HFCLKSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CMD */
-#define CMU_CMD_CALSTART (0x1UL << 3) /**< Calibration Start */
-#define _CMU_CMD_CALSTART_SHIFT 3 /**< Shift value for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_MASK 0x8UL /**< Bit mask for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTART_DEFAULT (_CMU_CMD_CALSTART_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP (0x1UL << 4) /**< Calibration Stop */
-#define _CMU_CMD_CALSTOP_SHIFT 4 /**< Shift value for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_MASK 0x10UL /**< Bit mask for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP_DEFAULT (_CMU_CMD_CALSTOP_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_CMD */
-
-/* Bit fields for CMU LFCLKSEL */
-#define _CMU_LFCLKSEL_RESETVALUE 0x00000005UL /**< Default value for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_MASK 0x0011000FUL /**< Mask for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_SHIFT 0 /**< Shift value for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_MASK 0x3UL /**< Bit mask for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DISABLED (_CMU_LFCLKSEL_LFA_DISABLED << 0) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DEFAULT (_CMU_LFCLKSEL_LFA_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFRCO (_CMU_LFCLKSEL_LFA_LFRCO << 0) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFXO (_CMU_LFCLKSEL_LFA_LFXO << 0) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 << 0) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_SHIFT 2 /**< Shift value for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_MASK 0xCUL /**< Bit mask for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DISABLED (_CMU_LFCLKSEL_LFB_DISABLED << 2) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DEFAULT (_CMU_LFCLKSEL_LFB_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFRCO (_CMU_LFCLKSEL_LFB_LFRCO << 2) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFXO (_CMU_LFCLKSEL_LFB_LFXO << 2) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 << 2) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE (0x1UL << 16) /**< Clock Select for LFA Extended */
-#define _CMU_LFCLKSEL_LFAE_SHIFT 16 /**< Shift value for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_MASK 0x10000UL /**< Bit mask for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DEFAULT (_CMU_LFCLKSEL_LFAE_DEFAULT << 16) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DISABLED (_CMU_LFCLKSEL_LFAE_DISABLED << 16) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_ULFRCO (_CMU_LFCLKSEL_LFAE_ULFRCO << 16) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE (0x1UL << 20) /**< Clock Select for LFB Extended */
-#define _CMU_LFCLKSEL_LFBE_SHIFT 20 /**< Shift value for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_MASK 0x100000UL /**< Bit mask for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DEFAULT (_CMU_LFCLKSEL_LFBE_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DISABLED (_CMU_LFCLKSEL_LFBE_DISABLED << 20) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_ULFRCO (_CMU_LFCLKSEL_LFBE_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-
-/* Bit fields for CMU STATUS */
-#define _CMU_STATUS_RESETVALUE 0x00000403UL /**< Default value for CMU_STATUS */
-#define _CMU_STATUS_MASK 0x00007FFFUL /**< Mask for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS (0x1UL << 0) /**< HFRCO Enable Status */
-#define _CMU_STATUS_HFRCOENS_SHIFT 0 /**< Shift value for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_MASK 0x1UL /**< Bit mask for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS_DEFAULT (_CMU_STATUS_HFRCOENS_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY (0x1UL << 1) /**< HFRCO Ready */
-#define _CMU_STATUS_HFRCORDY_SHIFT 1 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_MASK 0x2UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY_DEFAULT (_CMU_STATUS_HFRCORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS (0x1UL << 2) /**< HFXO Enable Status */
-#define _CMU_STATUS_HFXOENS_SHIFT 2 /**< Shift value for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_MASK 0x4UL /**< Bit mask for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS_DEFAULT (_CMU_STATUS_HFXOENS_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY (0x1UL << 3) /**< HFXO Ready */
-#define _CMU_STATUS_HFXORDY_SHIFT 3 /**< Shift value for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_MASK 0x8UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY_DEFAULT (_CMU_STATUS_HFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS (0x1UL << 4) /**< AUXHFRCO Enable Status */
-#define _CMU_STATUS_AUXHFRCOENS_SHIFT 4 /**< Shift value for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS_DEFAULT (_CMU_STATUS_AUXHFRCOENS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY (0x1UL << 5) /**< AUXHFRCO Ready */
-#define _CMU_STATUS_AUXHFRCORDY_SHIFT 5 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY_DEFAULT (_CMU_STATUS_AUXHFRCORDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS (0x1UL << 6) /**< LFRCO Enable Status */
-#define _CMU_STATUS_LFRCOENS_SHIFT 6 /**< Shift value for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_MASK 0x40UL /**< Bit mask for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS_DEFAULT (_CMU_STATUS_LFRCOENS_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY (0x1UL << 7) /**< LFRCO Ready */
-#define _CMU_STATUS_LFRCORDY_SHIFT 7 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_MASK 0x80UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY_DEFAULT (_CMU_STATUS_LFRCORDY_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS (0x1UL << 8) /**< LFXO Enable Status */
-#define _CMU_STATUS_LFXOENS_SHIFT 8 /**< Shift value for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_MASK 0x100UL /**< Bit mask for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS_DEFAULT (_CMU_STATUS_LFXOENS_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY (0x1UL << 9) /**< LFXO Ready */
-#define _CMU_STATUS_LFXORDY_SHIFT 9 /**< Shift value for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_MASK 0x200UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY_DEFAULT (_CMU_STATUS_LFXORDY_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL (0x1UL << 10) /**< HFRCO Selected */
-#define _CMU_STATUS_HFRCOSEL_SHIFT 10 /**< Shift value for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_MASK 0x400UL /**< Bit mask for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL_DEFAULT (_CMU_STATUS_HFRCOSEL_DEFAULT << 10) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL (0x1UL << 11) /**< HFXO Selected */
-#define _CMU_STATUS_HFXOSEL_SHIFT 11 /**< Shift value for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_MASK 0x800UL /**< Bit mask for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL_DEFAULT (_CMU_STATUS_HFXOSEL_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL (0x1UL << 12) /**< LFRCO Selected */
-#define _CMU_STATUS_LFRCOSEL_SHIFT 12 /**< Shift value for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_MASK 0x1000UL /**< Bit mask for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL_DEFAULT (_CMU_STATUS_LFRCOSEL_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL (0x1UL << 13) /**< LFXO Selected */
-#define _CMU_STATUS_LFXOSEL_SHIFT 13 /**< Shift value for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_MASK 0x2000UL /**< Bit mask for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL_DEFAULT (_CMU_STATUS_LFXOSEL_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY (0x1UL << 14) /**< Calibration Busy */
-#define _CMU_STATUS_CALBSY_SHIFT 14 /**< Shift value for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_MASK 0x4000UL /**< Bit mask for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY_DEFAULT (_CMU_STATUS_CALBSY_DEFAULT << 14) /**< Shifted mode DEFAULT for CMU_STATUS */
-
-/* Bit fields for CMU IF */
-#define _CMU_IF_RESETVALUE 0x00000001UL /**< Default value for CMU_IF */
-#define _CMU_IF_MASK 0x0000007FUL /**< Mask for CMU_IF */
-#define CMU_IF_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag */
-#define _CMU_IF_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFRCORDY_DEFAULT (_CMU_IF_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag */
-#define _CMU_IF_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY_DEFAULT (_CMU_IF_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag */
-#define _CMU_IF_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY_DEFAULT (_CMU_IF_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag */
-#define _CMU_IF_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY_DEFAULT (_CMU_IF_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag */
-#define _CMU_IF_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY_DEFAULT (_CMU_IF_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag */
-#define _CMU_IF_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IF_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IF_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY_DEFAULT (_CMU_IF_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag */
-#define _CMU_IF_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IF_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IF_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF_DEFAULT (_CMU_IF_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IF */
-
-/* Bit fields for CMU IFS */
-#define _CMU_IFS_RESETVALUE 0x00000000UL /**< Default value for CMU_IFS */
-#define _CMU_IFS_MASK 0x0000007FUL /**< Mask for CMU_IFS */
-#define CMU_IFS_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFRCORDY_DEFAULT (_CMU_IFS_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY_DEFAULT (_CMU_IFS_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY_DEFAULT (_CMU_IFS_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY_DEFAULT (_CMU_IFS_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY_DEFAULT (_CMU_IFS_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Set */
-#define _CMU_IFS_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY_DEFAULT (_CMU_IFS_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Set */
-#define _CMU_IFS_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFS_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFS_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF_DEFAULT (_CMU_IFS_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFS */
-
-/* Bit fields for CMU IFC */
-#define _CMU_IFC_RESETVALUE 0x00000000UL /**< Default value for CMU_IFC */
-#define _CMU_IFC_MASK 0x0000007FUL /**< Mask for CMU_IFC */
-#define CMU_IFC_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFRCORDY_DEFAULT (_CMU_IFC_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY_DEFAULT (_CMU_IFC_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY_DEFAULT (_CMU_IFC_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY_DEFAULT (_CMU_IFC_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY_DEFAULT (_CMU_IFC_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Clear */
-#define _CMU_IFC_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY_DEFAULT (_CMU_IFC_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Clear */
-#define _CMU_IFC_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFC_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFC_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF_DEFAULT (_CMU_IFC_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFC */
-
-/* Bit fields for CMU IEN */
-#define _CMU_IEN_RESETVALUE 0x00000000UL /**< Default value for CMU_IEN */
-#define _CMU_IEN_MASK 0x0000007FUL /**< Mask for CMU_IEN */
-#define CMU_IEN_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Enable */
-#define _CMU_IEN_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFRCORDY_DEFAULT (_CMU_IEN_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Enable */
-#define _CMU_IEN_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY_DEFAULT (_CMU_IEN_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Enable */
-#define _CMU_IEN_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY_DEFAULT (_CMU_IEN_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Enable */
-#define _CMU_IEN_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY_DEFAULT (_CMU_IEN_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Enable */
-#define _CMU_IEN_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY_DEFAULT (_CMU_IEN_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Enable */
-#define _CMU_IEN_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY_DEFAULT (_CMU_IEN_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Enable */
-#define _CMU_IEN_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IEN_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IEN_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF_DEFAULT (_CMU_IEN_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IEN */
-
-/* Bit fields for CMU HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_MASK 0x00000006UL /**< Mask for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA (0x1UL << 1) /**< Direct Memory Access Controller Clock Enable */
-#define _CMU_HFCORECLKEN0_DMA_SHIFT 1 /**< Shift value for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_MASK 0x2UL /**< Bit mask for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA_DEFAULT (_CMU_HFCORECLKEN0_DMA_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE (0x1UL << 2) /**< Low Energy Peripheral Interface Clock Enable */
-#define _CMU_HFCORECLKEN0_LE_SHIFT 2 /**< Shift value for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_MASK 0x4UL /**< Bit mask for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE_DEFAULT (_CMU_HFCORECLKEN0_LE_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-
-/* Bit fields for CMU HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_MASK 0x0000099FUL /**< Mask for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0 (0x1UL << 0) /**< Timer 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER0_SHIFT 0 /**< Shift value for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_MASK 0x1UL /**< Bit mask for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0_DEFAULT (_CMU_HFPERCLKEN0_TIMER0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1 (0x1UL << 1) /**< Timer 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER1_SHIFT 1 /**< Shift value for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_MASK 0x2UL /**< Bit mask for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1_DEFAULT (_CMU_HFPERCLKEN0_TIMER1_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0 (0x1UL << 2) /**< Analog Comparator 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_ACMP0_SHIFT 2 /**< Shift value for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_MASK 0x4UL /**< Bit mask for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0_DEFAULT (_CMU_HFPERCLKEN0_ACMP0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1 (0x1UL << 3) /**< Universal Synchronous/Asynchronous Receiver/Transmitter 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_USART1_SHIFT 3 /**< Shift value for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_MASK 0x8UL /**< Bit mask for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1_DEFAULT (_CMU_HFPERCLKEN0_USART1_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS (0x1UL << 4) /**< Peripheral Reflex System Clock Enable */
-#define _CMU_HFPERCLKEN0_PRS_SHIFT 4 /**< Shift value for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_MASK 0x10UL /**< Bit mask for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS_DEFAULT (_CMU_HFPERCLKEN0_PRS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO (0x1UL << 7) /**< General purpose Input/Output Clock Enable */
-#define _CMU_HFPERCLKEN0_GPIO_SHIFT 7 /**< Shift value for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_MASK 0x80UL /**< Bit mask for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO_DEFAULT (_CMU_HFPERCLKEN0_GPIO_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP (0x1UL << 8) /**< Voltage Comparator Clock Enable */
-#define _CMU_HFPERCLKEN0_VCMP_SHIFT 8 /**< Shift value for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_MASK 0x100UL /**< Bit mask for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP_DEFAULT (_CMU_HFPERCLKEN0_VCMP_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0 (0x1UL << 11) /**< I2C 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_I2C0_SHIFT 11 /**< Shift value for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_MASK 0x800UL /**< Bit mask for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0_DEFAULT (_CMU_HFPERCLKEN0_I2C0_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-
-/* Bit fields for CMU SYNCBUSY */
-#define _CMU_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for CMU_SYNCBUSY */
-#define _CMU_SYNCBUSY_MASK 0x00000055UL /**< Mask for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0 (0x1UL << 0) /**< Low Frequency A Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFACLKEN0_SHIFT 0 /**< Shift value for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_MASK 0x1UL /**< Bit mask for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0_DEFAULT (_CMU_SYNCBUSY_LFACLKEN0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0 (0x1UL << 2) /**< Low Frequency A Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFAPRESC0_SHIFT 2 /**< Shift value for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_MASK 0x4UL /**< Bit mask for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0_DEFAULT (_CMU_SYNCBUSY_LFAPRESC0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0 (0x1UL << 4) /**< Low Frequency B Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFBCLKEN0_SHIFT 4 /**< Shift value for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_MASK 0x10UL /**< Bit mask for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0_DEFAULT (_CMU_SYNCBUSY_LFBCLKEN0_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0 (0x1UL << 6) /**< Low Frequency B Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFBPRESC0_SHIFT 6 /**< Shift value for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_MASK 0x40UL /**< Bit mask for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0_DEFAULT (_CMU_SYNCBUSY_LFBPRESC0_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-
-/* Bit fields for CMU FREEZE */
-#define _CMU_FREEZE_RESETVALUE 0x00000000UL /**< Default value for CMU_FREEZE */
-#define _CMU_FREEZE_MASK 0x00000001UL /**< Mask for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _CMU_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_DEFAULT (_CMU_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_UPDATE (_CMU_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_FREEZE (_CMU_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for CMU_FREEZE */
-
-/* Bit fields for CMU LFACLKEN0 */
-#define _CMU_LFACLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFACLKEN0 */
-#define _CMU_LFACLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC (0x1UL << 0) /**< Real-Time Counter Clock Enable */
-#define _CMU_LFACLKEN0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_MASK 0x1UL /**< Bit mask for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC_DEFAULT (_CMU_LFACLKEN0_RTC_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFACLKEN0 */
-
-/* Bit fields for CMU LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0 (0x1UL << 0) /**< Low Energy UART 0 Clock Enable */
-#define _CMU_LFBCLKEN0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_MASK 0x1UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0_DEFAULT (_CMU_LFBCLKEN0_LEUART0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFBCLKEN0 */
-
-/* Bit fields for CMU LFAPRESC0 */
-#define _CMU_LFAPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_MASK 0x0000000FUL /**< Mask for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_MASK 0xFUL /**< Bit mask for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16 0x00000004UL /**< Mode DIV16 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32 0x00000005UL /**< Mode DIV32 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV64 0x00000006UL /**< Mode DIV64 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV128 0x00000007UL /**< Mode DIV128 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV256 0x00000008UL /**< Mode DIV256 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV512 0x00000009UL /**< Mode DIV512 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV1024 0x0000000AUL /**< Mode DIV1024 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2048 0x0000000BUL /**< Mode DIV2048 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4096 0x0000000CUL /**< Mode DIV4096 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8192 0x0000000DUL /**< Mode DIV8192 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16384 0x0000000EUL /**< Mode DIV16384 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32768 0x0000000FUL /**< Mode DIV32768 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1 (_CMU_LFAPRESC0_RTC_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2 (_CMU_LFAPRESC0_RTC_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4 (_CMU_LFAPRESC0_RTC_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8 (_CMU_LFAPRESC0_RTC_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16 (_CMU_LFAPRESC0_RTC_DIV16 << 0) /**< Shifted mode DIV16 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32 (_CMU_LFAPRESC0_RTC_DIV32 << 0) /**< Shifted mode DIV32 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV64 (_CMU_LFAPRESC0_RTC_DIV64 << 0) /**< Shifted mode DIV64 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV128 (_CMU_LFAPRESC0_RTC_DIV128 << 0) /**< Shifted mode DIV128 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV256 (_CMU_LFAPRESC0_RTC_DIV256 << 0) /**< Shifted mode DIV256 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV512 (_CMU_LFAPRESC0_RTC_DIV512 << 0) /**< Shifted mode DIV512 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1024 (_CMU_LFAPRESC0_RTC_DIV1024 << 0) /**< Shifted mode DIV1024 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2048 (_CMU_LFAPRESC0_RTC_DIV2048 << 0) /**< Shifted mode DIV2048 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4096 (_CMU_LFAPRESC0_RTC_DIV4096 << 0) /**< Shifted mode DIV4096 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8192 (_CMU_LFAPRESC0_RTC_DIV8192 << 0) /**< Shifted mode DIV8192 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16384 (_CMU_LFAPRESC0_RTC_DIV16384 << 0) /**< Shifted mode DIV16384 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32768 (_CMU_LFAPRESC0_RTC_DIV32768 << 0) /**< Shifted mode DIV32768 for CMU_LFAPRESC0 */
-
-/* Bit fields for CMU LFBPRESC0 */
-#define _CMU_LFBPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_MASK 0x00000003UL /**< Mask for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_MASK 0x3UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV1 (_CMU_LFBPRESC0_LEUART0_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV2 (_CMU_LFBPRESC0_LEUART0_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV4 (_CMU_LFBPRESC0_LEUART0_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV8 (_CMU_LFBPRESC0_LEUART0_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFBPRESC0 */
-
-/* Bit fields for CMU PCNTCTRL */
-#define _CMU_PCNTCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_MASK 0x00000003UL /**< Mask for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN (0x1UL << 0) /**< PCNT0 Clock Enable */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_SHIFT 0 /**< Shift value for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_MASK 0x1UL /**< Bit mask for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL (0x1UL << 1) /**< PCNT0 Clock Select */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_SHIFT 1 /**< Shift value for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_MASK 0x2UL /**< Bit mask for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK 0x00000000UL /**< Mode LFACLK for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 0x00000001UL /**< Mode PCNT0S0 for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK (_CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK << 1) /**< Shifted mode LFACLK for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 (_CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 << 1) /**< Shifted mode PCNT0S0 for CMU_PCNTCTRL */
-
-/* Bit fields for CMU ROUTE */
-#define _CMU_ROUTE_RESETVALUE 0x00000000UL /**< Default value for CMU_ROUTE */
-#define _CMU_ROUTE_MASK 0x0000001FUL /**< Mask for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN (0x1UL << 0) /**< CLKOUT0 Pin Enable */
-#define _CMU_ROUTE_CLKOUT0PEN_SHIFT 0 /**< Shift value for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_MASK 0x1UL /**< Bit mask for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN_DEFAULT (_CMU_ROUTE_CLKOUT0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN (0x1UL << 1) /**< CLKOUT1 Pin Enable */
-#define _CMU_ROUTE_CLKOUT1PEN_SHIFT 1 /**< Shift value for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_MASK 0x2UL /**< Bit mask for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN_DEFAULT (_CMU_ROUTE_CLKOUT1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_SHIFT 2 /**< Shift value for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_MASK 0x1CUL /**< Bit mask for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC0 (_CMU_ROUTE_LOCATION_LOC0 << 2) /**< Shifted mode LOC0 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_DEFAULT (_CMU_ROUTE_LOCATION_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC1 (_CMU_ROUTE_LOCATION_LOC1 << 2) /**< Shifted mode LOC1 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC2 (_CMU_ROUTE_LOCATION_LOC2 << 2) /**< Shifted mode LOC2 for CMU_ROUTE */
-
-/* Bit fields for CMU LOCK */
-#define _CMU_LOCK_RESETVALUE 0x00000000UL /**< Default value for CMU_LOCK */
-#define _CMU_LOCK_MASK 0x0000FFFFUL /**< Mask for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCK 0x0000580EUL /**< Mode UNLOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_DEFAULT (_CMU_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCK (_CMU_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCKED (_CMU_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCKED (_CMU_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCK (_CMU_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for CMU_LOCK */
-
-/** @} End of group EFM32ZG108F32_CMU */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_PRS_BitFields EFM32ZG108F32_PRS Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for PRS SWPULSE */
-#define _PRS_SWPULSE_RESETVALUE 0x00000000UL /**< Default value for PRS_SWPULSE */
-#define _PRS_SWPULSE_MASK 0x0000000FUL /**< Mask for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE (0x1UL << 0) /**< Channel 0 Pulse Generation */
-#define _PRS_SWPULSE_CH0PULSE_SHIFT 0 /**< Shift value for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_MASK 0x1UL /**< Bit mask for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE_DEFAULT (_PRS_SWPULSE_CH0PULSE_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE (0x1UL << 1) /**< Channel 1 Pulse Generation */
-#define _PRS_SWPULSE_CH1PULSE_SHIFT 1 /**< Shift value for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_MASK 0x2UL /**< Bit mask for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE_DEFAULT (_PRS_SWPULSE_CH1PULSE_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE (0x1UL << 2) /**< Channel 2 Pulse Generation */
-#define _PRS_SWPULSE_CH2PULSE_SHIFT 2 /**< Shift value for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_MASK 0x4UL /**< Bit mask for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE_DEFAULT (_PRS_SWPULSE_CH2PULSE_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE (0x1UL << 3) /**< Channel 3 Pulse Generation */
-#define _PRS_SWPULSE_CH3PULSE_SHIFT 3 /**< Shift value for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_MASK 0x8UL /**< Bit mask for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE_DEFAULT (_PRS_SWPULSE_CH3PULSE_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-
-/* Bit fields for PRS SWLEVEL */
-#define _PRS_SWLEVEL_RESETVALUE 0x00000000UL /**< Default value for PRS_SWLEVEL */
-#define _PRS_SWLEVEL_MASK 0x0000000FUL /**< Mask for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL (0x1UL << 0) /**< Channel 0 Software Level */
-#define _PRS_SWLEVEL_CH0LEVEL_SHIFT 0 /**< Shift value for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_MASK 0x1UL /**< Bit mask for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL_DEFAULT (_PRS_SWLEVEL_CH0LEVEL_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL (0x1UL << 1) /**< Channel 1 Software Level */
-#define _PRS_SWLEVEL_CH1LEVEL_SHIFT 1 /**< Shift value for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_MASK 0x2UL /**< Bit mask for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL_DEFAULT (_PRS_SWLEVEL_CH1LEVEL_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL (0x1UL << 2) /**< Channel 2 Software Level */
-#define _PRS_SWLEVEL_CH2LEVEL_SHIFT 2 /**< Shift value for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_MASK 0x4UL /**< Bit mask for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL_DEFAULT (_PRS_SWLEVEL_CH2LEVEL_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL (0x1UL << 3) /**< Channel 3 Software Level */
-#define _PRS_SWLEVEL_CH3LEVEL_SHIFT 3 /**< Shift value for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_MASK 0x8UL /**< Bit mask for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL_DEFAULT (_PRS_SWLEVEL_CH3LEVEL_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-
-/* Bit fields for PRS ROUTE */
-#define _PRS_ROUTE_RESETVALUE 0x00000000UL /**< Default value for PRS_ROUTE */
-#define _PRS_ROUTE_MASK 0x0000070FUL /**< Mask for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN (0x1UL << 0) /**< CH0 Pin Enable */
-#define _PRS_ROUTE_CH0PEN_SHIFT 0 /**< Shift value for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_MASK 0x1UL /**< Bit mask for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN_DEFAULT (_PRS_ROUTE_CH0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN (0x1UL << 1) /**< CH1 Pin Enable */
-#define _PRS_ROUTE_CH1PEN_SHIFT 1 /**< Shift value for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_MASK 0x2UL /**< Bit mask for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN_DEFAULT (_PRS_ROUTE_CH1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN (0x1UL << 2) /**< CH2 Pin Enable */
-#define _PRS_ROUTE_CH2PEN_SHIFT 2 /**< Shift value for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_MASK 0x4UL /**< Bit mask for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN_DEFAULT (_PRS_ROUTE_CH2PEN_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN (0x1UL << 3) /**< CH3 Pin Enable */
-#define _PRS_ROUTE_CH3PEN_SHIFT 3 /**< Shift value for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_MASK 0x8UL /**< Bit mask for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN_DEFAULT (_PRS_ROUTE_CH3PEN_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_SHIFT 8 /**< Shift value for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC0 (_PRS_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_DEFAULT (_PRS_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC1 (_PRS_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC2 (_PRS_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for PRS_ROUTE */
-
-/* Bit fields for PRS CH_CTRL */
-#define _PRS_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_MASK 0x133F0007UL /**< Mask for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_MASK 0x7UL /**< Bit mask for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_VCMPOUT 0x00000000UL /**< Mode VCMPOUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ACMP0OUT 0x00000000UL /**< Mode ACMP0OUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1IRTX 0x00000000UL /**< Mode USART1IRTX for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0UF 0x00000000UL /**< Mode TIMER0UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1UF 0x00000000UL /**< Mode TIMER1UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCOF 0x00000000UL /**< Mode RTCOF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN0 0x00000000UL /**< Mode GPIOPIN0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN8 0x00000000UL /**< Mode GPIOPIN8 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_PCNT0TCC 0x00000000UL /**< Mode PCNT0TCC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1TXC 0x00000001UL /**< Mode USART1TXC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0OF 0x00000001UL /**< Mode TIMER0OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1OF 0x00000001UL /**< Mode TIMER1OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP0 0x00000001UL /**< Mode RTCCOMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN1 0x00000001UL /**< Mode GPIOPIN1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN9 0x00000001UL /**< Mode GPIOPIN9 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000002UL /**< Mode USART1RXDATAV for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC0 0x00000002UL /**< Mode TIMER0CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC0 0x00000002UL /**< Mode TIMER1CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP1 0x00000002UL /**< Mode RTCCOMP1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN2 0x00000002UL /**< Mode GPIOPIN2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN10 0x00000002UL /**< Mode GPIOPIN10 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC1 0x00000003UL /**< Mode TIMER0CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC1 0x00000003UL /**< Mode TIMER1CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN3 0x00000003UL /**< Mode GPIOPIN3 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN11 0x00000003UL /**< Mode GPIOPIN11 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC2 0x00000004UL /**< Mode TIMER0CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC2 0x00000004UL /**< Mode TIMER1CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN4 0x00000004UL /**< Mode GPIOPIN4 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN12 0x00000004UL /**< Mode GPIOPIN12 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN5 0x00000005UL /**< Mode GPIOPIN5 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN13 0x00000005UL /**< Mode GPIOPIN13 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN6 0x00000006UL /**< Mode GPIOPIN6 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN14 0x00000006UL /**< Mode GPIOPIN14 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN7 0x00000007UL /**< Mode GPIOPIN7 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN15 0x00000007UL /**< Mode GPIOPIN15 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_VCMPOUT (_PRS_CH_CTRL_SIGSEL_VCMPOUT << 0) /**< Shifted mode VCMPOUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ACMP0OUT (_PRS_CH_CTRL_SIGSEL_ACMP0OUT << 0) /**< Shifted mode ACMP0OUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1IRTX (_PRS_CH_CTRL_SIGSEL_USART1IRTX << 0) /**< Shifted mode USART1IRTX for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0UF (_PRS_CH_CTRL_SIGSEL_TIMER0UF << 0) /**< Shifted mode TIMER0UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1UF (_PRS_CH_CTRL_SIGSEL_TIMER1UF << 0) /**< Shifted mode TIMER1UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCOF (_PRS_CH_CTRL_SIGSEL_RTCOF << 0) /**< Shifted mode RTCOF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN0 (_PRS_CH_CTRL_SIGSEL_GPIOPIN0 << 0) /**< Shifted mode GPIOPIN0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN8 (_PRS_CH_CTRL_SIGSEL_GPIOPIN8 << 0) /**< Shifted mode GPIOPIN8 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_PCNT0TCC (_PRS_CH_CTRL_SIGSEL_PCNT0TCC << 0) /**< Shifted mode PCNT0TCC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1TXC (_PRS_CH_CTRL_SIGSEL_USART1TXC << 0) /**< Shifted mode USART1TXC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0OF (_PRS_CH_CTRL_SIGSEL_TIMER0OF << 0) /**< Shifted mode TIMER0OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1OF (_PRS_CH_CTRL_SIGSEL_TIMER1OF << 0) /**< Shifted mode TIMER1OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP0 (_PRS_CH_CTRL_SIGSEL_RTCCOMP0 << 0) /**< Shifted mode RTCCOMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN1 (_PRS_CH_CTRL_SIGSEL_GPIOPIN1 << 0) /**< Shifted mode GPIOPIN1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN9 (_PRS_CH_CTRL_SIGSEL_GPIOPIN9 << 0) /**< Shifted mode GPIOPIN9 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1RXDATAV (_PRS_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC0 (_PRS_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC0 (_PRS_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP1 (_PRS_CH_CTRL_SIGSEL_RTCCOMP1 << 0) /**< Shifted mode RTCCOMP1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN2 (_PRS_CH_CTRL_SIGSEL_GPIOPIN2 << 0) /**< Shifted mode GPIOPIN2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN10 (_PRS_CH_CTRL_SIGSEL_GPIOPIN10 << 0) /**< Shifted mode GPIOPIN10 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC1 (_PRS_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC1 (_PRS_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN3 (_PRS_CH_CTRL_SIGSEL_GPIOPIN3 << 0) /**< Shifted mode GPIOPIN3 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN11 (_PRS_CH_CTRL_SIGSEL_GPIOPIN11 << 0) /**< Shifted mode GPIOPIN11 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC2 (_PRS_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC2 (_PRS_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN4 (_PRS_CH_CTRL_SIGSEL_GPIOPIN4 << 0) /**< Shifted mode GPIOPIN4 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN12 (_PRS_CH_CTRL_SIGSEL_GPIOPIN12 << 0) /**< Shifted mode GPIOPIN12 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN5 (_PRS_CH_CTRL_SIGSEL_GPIOPIN5 << 0) /**< Shifted mode GPIOPIN5 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN13 (_PRS_CH_CTRL_SIGSEL_GPIOPIN13 << 0) /**< Shifted mode GPIOPIN13 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN6 (_PRS_CH_CTRL_SIGSEL_GPIOPIN6 << 0) /**< Shifted mode GPIOPIN6 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN14 (_PRS_CH_CTRL_SIGSEL_GPIOPIN14 << 0) /**< Shifted mode GPIOPIN14 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN7 (_PRS_CH_CTRL_SIGSEL_GPIOPIN7 << 0) /**< Shifted mode GPIOPIN7 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN15 (_PRS_CH_CTRL_SIGSEL_GPIOPIN15 << 0) /**< Shifted mode GPIOPIN15 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_VCMP 0x00000001UL /**< Mode VCMP for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_ACMP0 0x00000002UL /**< Mode ACMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_USART1 0x00000011UL /**< Mode USART1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER0 0x0000001CUL /**< Mode TIMER0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER1 0x0000001DUL /**< Mode TIMER1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_RTC 0x00000028UL /**< Mode RTC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOL 0x00000030UL /**< Mode GPIOL for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOH 0x00000031UL /**< Mode GPIOH for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_PCNT0 0x00000036UL /**< Mode PCNT0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_NONE (_PRS_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_VCMP (_PRS_CH_CTRL_SOURCESEL_VCMP << 16) /**< Shifted mode VCMP for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_ACMP0 (_PRS_CH_CTRL_SOURCESEL_ACMP0 << 16) /**< Shifted mode ACMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_USART1 (_PRS_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER0 (_PRS_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER1 (_PRS_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_RTC (_PRS_CH_CTRL_SOURCESEL_RTC << 16) /**< Shifted mode RTC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOL (_PRS_CH_CTRL_SOURCESEL_GPIOL << 16) /**< Shifted mode GPIOL for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOH (_PRS_CH_CTRL_SOURCESEL_GPIOH << 16) /**< Shifted mode GPIOH for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_PCNT0 (_PRS_CH_CTRL_SOURCESEL_PCNT0 << 16) /**< Shifted mode PCNT0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_SHIFT 24 /**< Shift value for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_MASK 0x3000000UL /**< Bit mask for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_OFF 0x00000000UL /**< Mode OFF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_POSEDGE 0x00000001UL /**< Mode POSEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_NEGEDGE 0x00000002UL /**< Mode NEGEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_BOTHEDGES 0x00000003UL /**< Mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_DEFAULT (_PRS_CH_CTRL_EDSEL_DEFAULT << 24) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_OFF (_PRS_CH_CTRL_EDSEL_OFF << 24) /**< Shifted mode OFF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_POSEDGE (_PRS_CH_CTRL_EDSEL_POSEDGE << 24) /**< Shifted mode POSEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_NEGEDGE (_PRS_CH_CTRL_EDSEL_NEGEDGE << 24) /**< Shifted mode NEGEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_BOTHEDGES (_PRS_CH_CTRL_EDSEL_BOTHEDGES << 24) /**< Shifted mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC (0x1UL << 28) /**< Asynchronous reflex */
-#define _PRS_CH_CTRL_ASYNC_SHIFT 28 /**< Shift value for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_MASK 0x10000000UL /**< Bit mask for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC_DEFAULT (_PRS_CH_CTRL_ASYNC_DEFAULT << 28) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-
-/** @} End of group EFM32ZG108F32_PRS */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_UNLOCK EFM32ZG108F32 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG108F32_UNLOCK */
-
-/** @} End of group EFM32ZG108F32_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F32_Alternate_Function EFM32ZG108F32 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG108F32_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG108F32 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG108F32_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f4.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f4.h
deleted file mode 100644
index 380b9daa1d..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f4.h
+++ /dev/null
@@ -1,2188 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG108F4
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG108F4_H
-#define EFM32ZG108F4_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4 EFM32ZG108F4
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_Core EFM32ZG108F4 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG108F4_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG108F4_Part EFM32ZG108F4 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG108F4)
-#define EFM32ZG108F4 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG108F4" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG108F4 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00001000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG108F4_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_Peripheral_TypeDefs EFM32ZG108F4 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_dma_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_DMA EFM32ZG108F4 DMA
- * @{
- * @brief EFM32ZG108F4_DMA Register Declaration
- ******************************************************************************/
-typedef struct {
- __IM uint32_t STATUS; /**< DMA Status Registers */
- __OM uint32_t CONFIG; /**< DMA Configuration Register */
- __IOM uint32_t CTRLBASE; /**< Channel Control Data Base Pointer Register */
- __IM uint32_t ALTCTRLBASE; /**< Channel Alternate Control Data Base Pointer Register */
- __IM uint32_t CHWAITSTATUS; /**< Channel Wait on Request Status Register */
- __OM uint32_t CHSWREQ; /**< Channel Software Request Register */
- __IOM uint32_t CHUSEBURSTS; /**< Channel Useburst Set Register */
- __OM uint32_t CHUSEBURSTC; /**< Channel Useburst Clear Register */
- __IOM uint32_t CHREQMASKS; /**< Channel Request Mask Set Register */
- __OM uint32_t CHREQMASKC; /**< Channel Request Mask Clear Register */
- __IOM uint32_t CHENS; /**< Channel Enable Set Register */
- __OM uint32_t CHENC; /**< Channel Enable Clear Register */
- __IOM uint32_t CHALTS; /**< Channel Alternate Set Register */
- __OM uint32_t CHALTC; /**< Channel Alternate Clear Register */
- __IOM uint32_t CHPRIS; /**< Channel Priority Set Register */
- __OM uint32_t CHPRIC; /**< Channel Priority Clear Register */
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t ERRORC; /**< Bus Error Clear Register */
-
- uint32_t RESERVED1[880U]; /**< Reserved for future use **/
- __IM uint32_t CHREQSTATUS; /**< Channel Request Status */
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IM uint32_t CHSREQSTATUS; /**< Channel Single Request Status */
-
- uint32_t RESERVED3[121U]; /**< Reserved for future use **/
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable register */
-
- uint32_t RESERVED4[60U]; /**< Reserved registers */
- DMA_CH_TypeDef CH[4U]; /**< Channel registers */
-} DMA_TypeDef; /** DMA Register Declaration *//** @} */
-
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_CMU EFM32ZG108F4 CMU
- * @{
- * @brief EFM32ZG108F4_CMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< CMU Control Register */
- __IOM uint32_t HFCORECLKDIV; /**< High Frequency Core Clock Division Register */
- __IOM uint32_t HFPERCLKDIV; /**< High Frequency Peripheral Clock Division Register */
- __IOM uint32_t HFRCOCTRL; /**< HFRCO Control Register */
- __IOM uint32_t LFRCOCTRL; /**< LFRCO Control Register */
- __IOM uint32_t AUXHFRCOCTRL; /**< AUXHFRCO Control Register */
- __IOM uint32_t CALCTRL; /**< Calibration Control Register */
- __IOM uint32_t CALCNT; /**< Calibration Counter Register */
- __IOM uint32_t OSCENCMD; /**< Oscillator Enable/Disable Command Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IOM uint32_t LFCLKSEL; /**< Low Frequency Clock Select Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t HFCORECLKEN0; /**< High Frequency Core Clock Enable Register 0 */
- __IOM uint32_t HFPERCLKEN0; /**< High Frequency Peripheral Clock Enable Register 0 */
- uint32_t RESERVED0[2U]; /**< Reserved for future use **/
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IOM uint32_t LFACLKEN0; /**< Low Frequency A Clock Enable Register 0 (Async Reg) */
- uint32_t RESERVED1[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBCLKEN0; /**< Low Frequency B Clock Enable Register 0 (Async Reg) */
-
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFAPRESC0; /**< Low Frequency A Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED3[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBPRESC0; /**< Low Frequency B Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED4[1U]; /**< Reserved for future use **/
- __IOM uint32_t PCNTCTRL; /**< PCNT Control Register */
-
- uint32_t RESERVED5[1U]; /**< Reserved for future use **/
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
-} CMU_TypeDef; /** CMU Register Declaration *//** @} */
-
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_PRS EFM32ZG108F4 PRS
- * @{
- * @brief EFM32ZG108F4_PRS Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t SWPULSE; /**< Software Pulse Register */
- __IOM uint32_t SWLEVEL; /**< Software Level Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved registers */
- PRS_CH_TypeDef CH[4U]; /**< Channel registers */
-} PRS_TypeDef; /** PRS Register Declaration *//** @} */
-
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG108F4_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_Peripheral_Base EFM32ZG108F4 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG108F4_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_Peripheral_Declaration EFM32ZG108F4 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG108F4_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_BitFields EFM32ZG108F4 Bit Fields
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @addtogroup EFM32ZG108F4_PRS_Signals
- * @{
- * @brief PRS Signal names
- ******************************************************************************/
-#define PRS_VCMP_OUT ((1 << 16) + 0) /**< PRS Voltage comparator output */
-#define PRS_ACMP0_OUT ((2 << 16) + 0) /**< PRS Analog comparator output */
-#define PRS_USART1_IRTX ((17 << 16) + 0) /**< PRS USART 1 IRDA out */
-#define PRS_USART1_TXC ((17 << 16) + 1) /**< PRS USART 1 TX complete */
-#define PRS_USART1_RXDATAV ((17 << 16) + 2) /**< PRS USART 1 RX Data Valid */
-#define PRS_TIMER0_UF ((28 << 16) + 0) /**< PRS Timer 0 Underflow */
-#define PRS_TIMER0_OF ((28 << 16) + 1) /**< PRS Timer 0 Overflow */
-#define PRS_TIMER0_CC0 ((28 << 16) + 2) /**< PRS Timer 0 Compare/Capture 0 */
-#define PRS_TIMER0_CC1 ((28 << 16) + 3) /**< PRS Timer 0 Compare/Capture 1 */
-#define PRS_TIMER0_CC2 ((28 << 16) + 4) /**< PRS Timer 0 Compare/Capture 2 */
-#define PRS_TIMER1_UF ((29 << 16) + 0) /**< PRS Timer 1 Underflow */
-#define PRS_TIMER1_OF ((29 << 16) + 1) /**< PRS Timer 1 Overflow */
-#define PRS_TIMER1_CC0 ((29 << 16) + 2) /**< PRS Timer 1 Compare/Capture 0 */
-#define PRS_TIMER1_CC1 ((29 << 16) + 3) /**< PRS Timer 1 Compare/Capture 1 */
-#define PRS_TIMER1_CC2 ((29 << 16) + 4) /**< PRS Timer 1 Compare/Capture 2 */
-#define PRS_RTC_OF ((40 << 16) + 0) /**< PRS RTC Overflow */
-#define PRS_RTC_COMP0 ((40 << 16) + 1) /**< PRS RTC Compare 0 */
-#define PRS_RTC_COMP1 ((40 << 16) + 2) /**< PRS RTC Compare 1 */
-#define PRS_GPIO_PIN0 ((48 << 16) + 0) /**< PRS GPIO pin 0 */
-#define PRS_GPIO_PIN1 ((48 << 16) + 1) /**< PRS GPIO pin 1 */
-#define PRS_GPIO_PIN2 ((48 << 16) + 2) /**< PRS GPIO pin 2 */
-#define PRS_GPIO_PIN3 ((48 << 16) + 3) /**< PRS GPIO pin 3 */
-#define PRS_GPIO_PIN4 ((48 << 16) + 4) /**< PRS GPIO pin 4 */
-#define PRS_GPIO_PIN5 ((48 << 16) + 5) /**< PRS GPIO pin 5 */
-#define PRS_GPIO_PIN6 ((48 << 16) + 6) /**< PRS GPIO pin 6 */
-#define PRS_GPIO_PIN7 ((48 << 16) + 7) /**< PRS GPIO pin 7 */
-#define PRS_GPIO_PIN8 ((49 << 16) + 0) /**< PRS GPIO pin 8 */
-#define PRS_GPIO_PIN9 ((49 << 16) + 1) /**< PRS GPIO pin 9 */
-#define PRS_GPIO_PIN10 ((49 << 16) + 2) /**< PRS GPIO pin 10 */
-#define PRS_GPIO_PIN11 ((49 << 16) + 3) /**< PRS GPIO pin 11 */
-#define PRS_GPIO_PIN12 ((49 << 16) + 4) /**< PRS GPIO pin 12 */
-#define PRS_GPIO_PIN13 ((49 << 16) + 5) /**< PRS GPIO pin 13 */
-#define PRS_GPIO_PIN14 ((49 << 16) + 6) /**< PRS GPIO pin 14 */
-#define PRS_GPIO_PIN15 ((49 << 16) + 7) /**< PRS GPIO pin 15 */
-#define PRS_PCNT0_TCC ((54 << 16) + 0) /**< PRS Triggered compare match */
-
-/** @} End of group EFM32ZG108F4_PRS */
-
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_DMA_BitFields EFM32ZG108F4_DMA Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for DMA STATUS */
-#define _DMA_STATUS_RESETVALUE 0x10030000UL /**< Default value for DMA_STATUS */
-#define _DMA_STATUS_MASK 0x001F00F1UL /**< Mask for DMA_STATUS */
-#define DMA_STATUS_EN (0x1UL << 0) /**< DMA Enable Status */
-#define _DMA_STATUS_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_STATUS_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_STATUS_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_EN_DEFAULT (_DMA_STATUS_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_SHIFT 4 /**< Shift value for DMA_STATE */
-#define _DMA_STATUS_STATE_MASK 0xF0UL /**< Bit mask for DMA_STATE */
-#define _DMA_STATUS_STATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_IDLE 0x00000000UL /**< Mode IDLE for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDCHCTRLDATA 0x00000001UL /**< Mode RDCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCENDPTR 0x00000002UL /**< Mode RDSRCENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDDSTENDPTR 0x00000003UL /**< Mode RDDSTENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCDATA 0x00000004UL /**< Mode RDSRCDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRDSTDATA 0x00000005UL /**< Mode WRDSTDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WAITREQCLR 0x00000006UL /**< Mode WAITREQCLR for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRCHCTRLDATA 0x00000007UL /**< Mode WRCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_STALLED 0x00000008UL /**< Mode STALLED for DMA_STATUS */
-#define _DMA_STATUS_STATE_DONE 0x00000009UL /**< Mode DONE for DMA_STATUS */
-#define _DMA_STATUS_STATE_PERSCATTRANS 0x0000000AUL /**< Mode PERSCATTRANS for DMA_STATUS */
-#define DMA_STATUS_STATE_DEFAULT (_DMA_STATUS_STATE_DEFAULT << 4) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_STATE_IDLE (_DMA_STATUS_STATE_IDLE << 4) /**< Shifted mode IDLE for DMA_STATUS */
-#define DMA_STATUS_STATE_RDCHCTRLDATA (_DMA_STATUS_STATE_RDCHCTRLDATA << 4) /**< Shifted mode RDCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCENDPTR (_DMA_STATUS_STATE_RDSRCENDPTR << 4) /**< Shifted mode RDSRCENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDDSTENDPTR (_DMA_STATUS_STATE_RDDSTENDPTR << 4) /**< Shifted mode RDDSTENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCDATA (_DMA_STATUS_STATE_RDSRCDATA << 4) /**< Shifted mode RDSRCDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WRDSTDATA (_DMA_STATUS_STATE_WRDSTDATA << 4) /**< Shifted mode WRDSTDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WAITREQCLR (_DMA_STATUS_STATE_WAITREQCLR << 4) /**< Shifted mode WAITREQCLR for DMA_STATUS */
-#define DMA_STATUS_STATE_WRCHCTRLDATA (_DMA_STATUS_STATE_WRCHCTRLDATA << 4) /**< Shifted mode WRCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_STALLED (_DMA_STATUS_STATE_STALLED << 4) /**< Shifted mode STALLED for DMA_STATUS */
-#define DMA_STATUS_STATE_DONE (_DMA_STATUS_STATE_DONE << 4) /**< Shifted mode DONE for DMA_STATUS */
-#define DMA_STATUS_STATE_PERSCATTRANS (_DMA_STATUS_STATE_PERSCATTRANS << 4) /**< Shifted mode PERSCATTRANS for DMA_STATUS */
-#define _DMA_STATUS_CHNUM_SHIFT 16 /**< Shift value for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_MASK 0x1F0000UL /**< Bit mask for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_DEFAULT 0x00000003UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_CHNUM_DEFAULT (_DMA_STATUS_CHNUM_DEFAULT << 16) /**< Shifted mode DEFAULT for DMA_STATUS */
-
-/* Bit fields for DMA CONFIG */
-#define _DMA_CONFIG_RESETVALUE 0x00000000UL /**< Default value for DMA_CONFIG */
-#define _DMA_CONFIG_MASK 0x00000021UL /**< Mask for DMA_CONFIG */
-#define DMA_CONFIG_EN (0x1UL << 0) /**< Enable DMA */
-#define _DMA_CONFIG_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_CONFIG_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_CONFIG_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_EN_DEFAULT (_DMA_CONFIG_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT (0x1UL << 5) /**< Channel Protection Control */
-#define _DMA_CONFIG_CHPROT_SHIFT 5 /**< Shift value for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_MASK 0x20UL /**< Bit mask for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT_DEFAULT (_DMA_CONFIG_CHPROT_DEFAULT << 5) /**< Shifted mode DEFAULT for DMA_CONFIG */
-
-/* Bit fields for DMA CTRLBASE */
-#define _DMA_CTRLBASE_RESETVALUE 0x00000000UL /**< Default value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_SHIFT 0 /**< Shift value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CTRLBASE */
-#define DMA_CTRLBASE_CTRLBASE_DEFAULT (_DMA_CTRLBASE_CTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CTRLBASE */
-
-/* Bit fields for DMA ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_RESETVALUE 0x00000040UL /**< Default value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_SHIFT 0 /**< Shift value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT 0x00000040UL /**< Mode DEFAULT for DMA_ALTCTRLBASE */
-#define DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT (_DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ALTCTRLBASE */
-
-/* Bit fields for DMA CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_RESETVALUE 0x0000000FUL /**< Default value for DMA_CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS (0x1UL << 0) /**< Channel 0 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_SHIFT 0 /**< Shift value for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS (0x1UL << 1) /**< Channel 1 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_SHIFT 1 /**< Shift value for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS (0x1UL << 2) /**< Channel 2 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_SHIFT 2 /**< Shift value for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS (0x1UL << 3) /**< Channel 3 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_SHIFT 3 /**< Shift value for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-
-/* Bit fields for DMA CHSWREQ */
-#define _DMA_CHSWREQ_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSWREQ */
-#define _DMA_CHSWREQ_MASK 0x0000000FUL /**< Mask for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ (0x1UL << 0) /**< Channel 0 Software Request */
-#define _DMA_CHSWREQ_CH0SWREQ_SHIFT 0 /**< Shift value for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_MASK 0x1UL /**< Bit mask for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ_DEFAULT (_DMA_CHSWREQ_CH0SWREQ_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ (0x1UL << 1) /**< Channel 1 Software Request */
-#define _DMA_CHSWREQ_CH1SWREQ_SHIFT 1 /**< Shift value for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_MASK 0x2UL /**< Bit mask for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ_DEFAULT (_DMA_CHSWREQ_CH1SWREQ_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ (0x1UL << 2) /**< Channel 2 Software Request */
-#define _DMA_CHSWREQ_CH2SWREQ_SHIFT 2 /**< Shift value for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_MASK 0x4UL /**< Bit mask for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ_DEFAULT (_DMA_CHSWREQ_CH2SWREQ_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ (0x1UL << 3) /**< Channel 3 Software Request */
-#define _DMA_CHSWREQ_CH3SWREQ_SHIFT 3 /**< Shift value for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_MASK 0x8UL /**< Bit mask for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ_DEFAULT (_DMA_CHSWREQ_CH3SWREQ_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-
-/* Bit fields for DMA CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS (0x1UL << 0) /**< Channel 0 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST 0x00000000UL /**< Mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY 0x00000001UL /**< Mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST (_DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST << 0) /**< Shifted mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY (_DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY << 0) /**< Shifted mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS (0x1UL << 1) /**< Channel 1 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS (0x1UL << 2) /**< Channel 2 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS (0x1UL << 3) /**< Channel 3 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-
-/* Bit fields for DMA CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC (0x1UL << 0) /**< Channel 0 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC (0x1UL << 1) /**< Channel 1 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC (0x1UL << 2) /**< Channel 2 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC (0x1UL << 3) /**< Channel 3 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-
-/* Bit fields for DMA CHREQMASKS */
-#define _DMA_CHREQMASKS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKS */
-#define _DMA_CHREQMASKS_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS (0x1UL << 0) /**< Channel 0 Request Mask Set */
-#define _DMA_CHREQMASKS_CH0REQMASKS_SHIFT 0 /**< Shift value for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH0REQMASKS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS (0x1UL << 1) /**< Channel 1 Request Mask Set */
-#define _DMA_CHREQMASKS_CH1REQMASKS_SHIFT 1 /**< Shift value for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH1REQMASKS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS (0x1UL << 2) /**< Channel 2 Request Mask Set */
-#define _DMA_CHREQMASKS_CH2REQMASKS_SHIFT 2 /**< Shift value for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH2REQMASKS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS (0x1UL << 3) /**< Channel 3 Request Mask Set */
-#define _DMA_CHREQMASKS_CH3REQMASKS_SHIFT 3 /**< Shift value for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH3REQMASKS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-
-/* Bit fields for DMA CHREQMASKC */
-#define _DMA_CHREQMASKC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKC */
-#define _DMA_CHREQMASKC_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC (0x1UL << 0) /**< Channel 0 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH0REQMASKC_SHIFT 0 /**< Shift value for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH0REQMASKC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC (0x1UL << 1) /**< Channel 1 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH1REQMASKC_SHIFT 1 /**< Shift value for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH1REQMASKC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC (0x1UL << 2) /**< Channel 2 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH2REQMASKC_SHIFT 2 /**< Shift value for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH2REQMASKC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC (0x1UL << 3) /**< Channel 3 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH3REQMASKC_SHIFT 3 /**< Shift value for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH3REQMASKC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-
-/* Bit fields for DMA CHENS */
-#define _DMA_CHENS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENS */
-#define _DMA_CHENS_MASK 0x0000000FUL /**< Mask for DMA_CHENS */
-#define DMA_CHENS_CH0ENS (0x1UL << 0) /**< Channel 0 Enable Set */
-#define _DMA_CHENS_CH0ENS_SHIFT 0 /**< Shift value for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_MASK 0x1UL /**< Bit mask for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH0ENS_DEFAULT (_DMA_CHENS_CH0ENS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS (0x1UL << 1) /**< Channel 1 Enable Set */
-#define _DMA_CHENS_CH1ENS_SHIFT 1 /**< Shift value for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_MASK 0x2UL /**< Bit mask for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS_DEFAULT (_DMA_CHENS_CH1ENS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS (0x1UL << 2) /**< Channel 2 Enable Set */
-#define _DMA_CHENS_CH2ENS_SHIFT 2 /**< Shift value for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_MASK 0x4UL /**< Bit mask for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS_DEFAULT (_DMA_CHENS_CH2ENS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS (0x1UL << 3) /**< Channel 3 Enable Set */
-#define _DMA_CHENS_CH3ENS_SHIFT 3 /**< Shift value for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_MASK 0x8UL /**< Bit mask for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS_DEFAULT (_DMA_CHENS_CH3ENS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENS */
-
-/* Bit fields for DMA CHENC */
-#define _DMA_CHENC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENC */
-#define _DMA_CHENC_MASK 0x0000000FUL /**< Mask for DMA_CHENC */
-#define DMA_CHENC_CH0ENC (0x1UL << 0) /**< Channel 0 Enable Clear */
-#define _DMA_CHENC_CH0ENC_SHIFT 0 /**< Shift value for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_MASK 0x1UL /**< Bit mask for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH0ENC_DEFAULT (_DMA_CHENC_CH0ENC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC (0x1UL << 1) /**< Channel 1 Enable Clear */
-#define _DMA_CHENC_CH1ENC_SHIFT 1 /**< Shift value for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_MASK 0x2UL /**< Bit mask for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC_DEFAULT (_DMA_CHENC_CH1ENC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC (0x1UL << 2) /**< Channel 2 Enable Clear */
-#define _DMA_CHENC_CH2ENC_SHIFT 2 /**< Shift value for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_MASK 0x4UL /**< Bit mask for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC_DEFAULT (_DMA_CHENC_CH2ENC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC (0x1UL << 3) /**< Channel 3 Enable Clear */
-#define _DMA_CHENC_CH3ENC_SHIFT 3 /**< Shift value for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_MASK 0x8UL /**< Bit mask for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC_DEFAULT (_DMA_CHENC_CH3ENC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENC */
-
-/* Bit fields for DMA CHALTS */
-#define _DMA_CHALTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTS */
-#define _DMA_CHALTS_MASK 0x0000000FUL /**< Mask for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS (0x1UL << 0) /**< Channel 0 Alternate Structure Set */
-#define _DMA_CHALTS_CH0ALTS_SHIFT 0 /**< Shift value for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_MASK 0x1UL /**< Bit mask for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS_DEFAULT (_DMA_CHALTS_CH0ALTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS (0x1UL << 1) /**< Channel 1 Alternate Structure Set */
-#define _DMA_CHALTS_CH1ALTS_SHIFT 1 /**< Shift value for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_MASK 0x2UL /**< Bit mask for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS_DEFAULT (_DMA_CHALTS_CH1ALTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS (0x1UL << 2) /**< Channel 2 Alternate Structure Set */
-#define _DMA_CHALTS_CH2ALTS_SHIFT 2 /**< Shift value for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_MASK 0x4UL /**< Bit mask for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS_DEFAULT (_DMA_CHALTS_CH2ALTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS (0x1UL << 3) /**< Channel 3 Alternate Structure Set */
-#define _DMA_CHALTS_CH3ALTS_SHIFT 3 /**< Shift value for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_MASK 0x8UL /**< Bit mask for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS_DEFAULT (_DMA_CHALTS_CH3ALTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTS */
-
-/* Bit fields for DMA CHALTC */
-#define _DMA_CHALTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTC */
-#define _DMA_CHALTC_MASK 0x0000000FUL /**< Mask for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC (0x1UL << 0) /**< Channel 0 Alternate Clear */
-#define _DMA_CHALTC_CH0ALTC_SHIFT 0 /**< Shift value for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_MASK 0x1UL /**< Bit mask for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC_DEFAULT (_DMA_CHALTC_CH0ALTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC (0x1UL << 1) /**< Channel 1 Alternate Clear */
-#define _DMA_CHALTC_CH1ALTC_SHIFT 1 /**< Shift value for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_MASK 0x2UL /**< Bit mask for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC_DEFAULT (_DMA_CHALTC_CH1ALTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC (0x1UL << 2) /**< Channel 2 Alternate Clear */
-#define _DMA_CHALTC_CH2ALTC_SHIFT 2 /**< Shift value for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_MASK 0x4UL /**< Bit mask for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC_DEFAULT (_DMA_CHALTC_CH2ALTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC (0x1UL << 3) /**< Channel 3 Alternate Clear */
-#define _DMA_CHALTC_CH3ALTC_SHIFT 3 /**< Shift value for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_MASK 0x8UL /**< Bit mask for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC_DEFAULT (_DMA_CHALTC_CH3ALTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTC */
-
-/* Bit fields for DMA CHPRIS */
-#define _DMA_CHPRIS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIS */
-#define _DMA_CHPRIS_MASK 0x0000000FUL /**< Mask for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS (0x1UL << 0) /**< Channel 0 High Priority Set */
-#define _DMA_CHPRIS_CH0PRIS_SHIFT 0 /**< Shift value for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_MASK 0x1UL /**< Bit mask for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS_DEFAULT (_DMA_CHPRIS_CH0PRIS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS (0x1UL << 1) /**< Channel 1 High Priority Set */
-#define _DMA_CHPRIS_CH1PRIS_SHIFT 1 /**< Shift value for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_MASK 0x2UL /**< Bit mask for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS_DEFAULT (_DMA_CHPRIS_CH1PRIS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS (0x1UL << 2) /**< Channel 2 High Priority Set */
-#define _DMA_CHPRIS_CH2PRIS_SHIFT 2 /**< Shift value for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_MASK 0x4UL /**< Bit mask for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS_DEFAULT (_DMA_CHPRIS_CH2PRIS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS (0x1UL << 3) /**< Channel 3 High Priority Set */
-#define _DMA_CHPRIS_CH3PRIS_SHIFT 3 /**< Shift value for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_MASK 0x8UL /**< Bit mask for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS_DEFAULT (_DMA_CHPRIS_CH3PRIS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-
-/* Bit fields for DMA CHPRIC */
-#define _DMA_CHPRIC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIC */
-#define _DMA_CHPRIC_MASK 0x0000000FUL /**< Mask for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC (0x1UL << 0) /**< Channel 0 High Priority Clear */
-#define _DMA_CHPRIC_CH0PRIC_SHIFT 0 /**< Shift value for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_MASK 0x1UL /**< Bit mask for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC_DEFAULT (_DMA_CHPRIC_CH0PRIC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC (0x1UL << 1) /**< Channel 1 High Priority Clear */
-#define _DMA_CHPRIC_CH1PRIC_SHIFT 1 /**< Shift value for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_MASK 0x2UL /**< Bit mask for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC_DEFAULT (_DMA_CHPRIC_CH1PRIC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC (0x1UL << 2) /**< Channel 2 High Priority Clear */
-#define _DMA_CHPRIC_CH2PRIC_SHIFT 2 /**< Shift value for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_MASK 0x4UL /**< Bit mask for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC_DEFAULT (_DMA_CHPRIC_CH2PRIC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC (0x1UL << 3) /**< Channel 3 High Priority Clear */
-#define _DMA_CHPRIC_CH3PRIC_SHIFT 3 /**< Shift value for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_MASK 0x8UL /**< Bit mask for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC_DEFAULT (_DMA_CHPRIC_CH3PRIC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-
-/* Bit fields for DMA ERRORC */
-#define _DMA_ERRORC_RESETVALUE 0x00000000UL /**< Default value for DMA_ERRORC */
-#define _DMA_ERRORC_MASK 0x00000001UL /**< Mask for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC (0x1UL << 0) /**< Bus Error Clear */
-#define _DMA_ERRORC_ERRORC_SHIFT 0 /**< Shift value for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_MASK 0x1UL /**< Bit mask for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC_DEFAULT (_DMA_ERRORC_ERRORC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ERRORC */
-
-/* Bit fields for DMA CHREQSTATUS */
-#define _DMA_CHREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQSTATUS */
-#define _DMA_CHREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS (0x1UL << 0) /**< Channel 0 Request Status */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS (0x1UL << 1) /**< Channel 1 Request Status */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS (0x1UL << 2) /**< Channel 2 Request Status */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS (0x1UL << 3) /**< Channel 3 Request Status */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-
-/* Bit fields for DMA CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS (0x1UL << 0) /**< Channel 0 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS (0x1UL << 1) /**< Channel 1 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS (0x1UL << 2) /**< Channel 2 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS (0x1UL << 3) /**< Channel 3 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-
-/* Bit fields for DMA IF */
-#define _DMA_IF_RESETVALUE 0x00000000UL /**< Default value for DMA_IF */
-#define _DMA_IF_MASK 0x8000000FUL /**< Mask for DMA_IF */
-#define DMA_IF_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag */
-#define _DMA_IF_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH0DONE_DEFAULT (_DMA_IF_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag */
-#define _DMA_IF_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE_DEFAULT (_DMA_IF_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag */
-#define _DMA_IF_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE_DEFAULT (_DMA_IF_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag */
-#define _DMA_IF_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE_DEFAULT (_DMA_IF_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag */
-#define _DMA_IF_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IF_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IF_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR_DEFAULT (_DMA_IF_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IF */
-
-/* Bit fields for DMA IFS */
-#define _DMA_IFS_RESETVALUE 0x00000000UL /**< Default value for DMA_IFS */
-#define _DMA_IFS_MASK 0x8000000FUL /**< Mask for DMA_IFS */
-#define DMA_IFS_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH0DONE_DEFAULT (_DMA_IFS_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE_DEFAULT (_DMA_IFS_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE_DEFAULT (_DMA_IFS_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE_DEFAULT (_DMA_IFS_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Set */
-#define _DMA_IFS_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFS_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFS_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR_DEFAULT (_DMA_IFS_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFS */
-
-/* Bit fields for DMA IFC */
-#define _DMA_IFC_RESETVALUE 0x00000000UL /**< Default value for DMA_IFC */
-#define _DMA_IFC_MASK 0x8000000FUL /**< Mask for DMA_IFC */
-#define DMA_IFC_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH0DONE_DEFAULT (_DMA_IFC_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE_DEFAULT (_DMA_IFC_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE_DEFAULT (_DMA_IFC_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE_DEFAULT (_DMA_IFC_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Clear */
-#define _DMA_IFC_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFC_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFC_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR_DEFAULT (_DMA_IFC_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFC */
-
-/* Bit fields for DMA IEN */
-#define _DMA_IEN_RESETVALUE 0x00000000UL /**< Default value for DMA_IEN */
-#define _DMA_IEN_MASK 0x8000000FUL /**< Mask for DMA_IEN */
-#define DMA_IEN_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Enable */
-#define _DMA_IEN_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH0DONE_DEFAULT (_DMA_IEN_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Enable */
-#define _DMA_IEN_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE_DEFAULT (_DMA_IEN_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Enable */
-#define _DMA_IEN_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE_DEFAULT (_DMA_IEN_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Enable */
-#define _DMA_IEN_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE_DEFAULT (_DMA_IEN_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Enable */
-#define _DMA_IEN_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IEN_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IEN_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR_DEFAULT (_DMA_IEN_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IEN */
-
-/* Bit fields for DMA CH_CTRL */
-#define _DMA_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_MASK 0x003F000FUL /**< Mask for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_MASK 0xFUL /**< Bit mask for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000000UL /**< Mode USART1RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV 0x00000000UL /**< Mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0RXDATAV 0x00000000UL /**< Mode I2C0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0UFOF 0x00000000UL /**< Mode TIMER0UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1UFOF 0x00000000UL /**< Mode TIMER1UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_MSCWDATA 0x00000000UL /**< Mode MSCWDATA for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBL 0x00000001UL /**< Mode USART1TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXBL 0x00000001UL /**< Mode LEUART0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0TXBL 0x00000001UL /**< Mode I2C0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC0 0x00000001UL /**< Mode TIMER0CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC0 0x00000001UL /**< Mode TIMER1CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXEMPTY 0x00000002UL /**< Mode USART1TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY 0x00000002UL /**< Mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC1 0x00000002UL /**< Mode TIMER0CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC1 0x00000002UL /**< Mode TIMER1CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT 0x00000003UL /**< Mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC2 0x00000003UL /**< Mode TIMER0CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC2 0x00000003UL /**< Mode TIMER1CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT 0x00000004UL /**< Mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAV (_DMA_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV (_DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV << 0) /**< Shifted mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0RXDATAV (_DMA_CH_CTRL_SIGSEL_I2C0RXDATAV << 0) /**< Shifted mode I2C0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0UFOF (_DMA_CH_CTRL_SIGSEL_TIMER0UFOF << 0) /**< Shifted mode TIMER0UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1UFOF (_DMA_CH_CTRL_SIGSEL_TIMER1UFOF << 0) /**< Shifted mode TIMER1UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_MSCWDATA (_DMA_CH_CTRL_SIGSEL_MSCWDATA << 0) /**< Shifted mode MSCWDATA for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBL (_DMA_CH_CTRL_SIGSEL_USART1TXBL << 0) /**< Shifted mode USART1TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXBL (_DMA_CH_CTRL_SIGSEL_LEUART0TXBL << 0) /**< Shifted mode LEUART0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0TXBL (_DMA_CH_CTRL_SIGSEL_I2C0TXBL << 0) /**< Shifted mode I2C0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC0 (_DMA_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC0 (_DMA_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXEMPTY (_DMA_CH_CTRL_SIGSEL_USART1TXEMPTY << 0) /**< Shifted mode USART1TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY (_DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY << 0) /**< Shifted mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC1 (_DMA_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC1 (_DMA_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT (_DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT << 0) /**< Shifted mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC2 (_DMA_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC2 (_DMA_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT (_DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT << 0) /**< Shifted mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_USART1 0x0000000DUL /**< Mode USART1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_LEUART0 0x00000010UL /**< Mode LEUART0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_I2C0 0x00000014UL /**< Mode I2C0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER0 0x00000018UL /**< Mode TIMER0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER1 0x00000019UL /**< Mode TIMER1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_MSC 0x00000030UL /**< Mode MSC for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_NONE (_DMA_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_USART1 (_DMA_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_LEUART0 (_DMA_CH_CTRL_SOURCESEL_LEUART0 << 16) /**< Shifted mode LEUART0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_I2C0 (_DMA_CH_CTRL_SOURCESEL_I2C0 << 16) /**< Shifted mode I2C0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER0 (_DMA_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER1 (_DMA_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_MSC (_DMA_CH_CTRL_SOURCESEL_MSC << 16) /**< Shifted mode MSC for DMA_CH_CTRL */
-
-/** @} End of group EFM32ZG108F4_DMA */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_CMU_BitFields EFM32ZG108F4_CMU Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for CMU CTRL */
-#define _CMU_CTRL_RESETVALUE 0x000C262CUL /**< Default value for CMU_CTRL */
-#define _CMU_CTRL_MASK 0x07FE3EEFUL /**< Mask for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_SHIFT 0 /**< Shift value for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_MASK 0x3UL /**< Bit mask for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DEFAULT (_CMU_CTRL_HFXOMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_XTAL (_CMU_CTRL_HFXOMODE_XTAL << 0) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_BUFEXTCLK (_CMU_CTRL_HFXOMODE_BUFEXTCLK << 0) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DIGEXTCLK (_CMU_CTRL_HFXOMODE_DIGEXTCLK << 0) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_SHIFT 2 /**< Shift value for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_MASK 0xCUL /**< Bit mask for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_50PCENT 0x00000000UL /**< Mode 50PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_70PCENT 0x00000001UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_80PCENT 0x00000002UL /**< Mode 80PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_100PCENT 0x00000003UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_50PCENT (_CMU_CTRL_HFXOBOOST_50PCENT << 2) /**< Shifted mode 50PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_70PCENT (_CMU_CTRL_HFXOBOOST_70PCENT << 2) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_80PCENT (_CMU_CTRL_HFXOBOOST_80PCENT << 2) /**< Shifted mode 80PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_DEFAULT (_CMU_CTRL_HFXOBOOST_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_100PCENT (_CMU_CTRL_HFXOBOOST_100PCENT << 2) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBUFCUR_SHIFT 5 /**< Shift value for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_MASK 0x60UL /**< Bit mask for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBUFCUR_DEFAULT (_CMU_CTRL_HFXOBUFCUR_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN (0x1UL << 7) /**< HFXO Glitch Detector Enable */
-#define _CMU_CTRL_HFXOGLITCHDETEN_SHIFT 7 /**< Shift value for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_MASK 0x80UL /**< Bit mask for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN_DEFAULT (_CMU_CTRL_HFXOGLITCHDETEN_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_SHIFT 9 /**< Shift value for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_MASK 0x600UL /**< Bit mask for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_256CYCLES 0x00000001UL /**< Mode 256CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_1KCYCLES 0x00000002UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_16KCYCLES 0x00000003UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_8CYCLES (_CMU_CTRL_HFXOTIMEOUT_8CYCLES << 9) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_256CYCLES (_CMU_CTRL_HFXOTIMEOUT_256CYCLES << 9) /**< Shifted mode 256CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_1KCYCLES (_CMU_CTRL_HFXOTIMEOUT_1KCYCLES << 9) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_DEFAULT (_CMU_CTRL_HFXOTIMEOUT_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_16KCYCLES (_CMU_CTRL_HFXOTIMEOUT_16KCYCLES << 9) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_SHIFT 11 /**< Shift value for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_MASK 0x1800UL /**< Bit mask for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DEFAULT (_CMU_CTRL_LFXOMODE_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_XTAL (_CMU_CTRL_LFXOMODE_XTAL << 11) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_BUFEXTCLK (_CMU_CTRL_LFXOMODE_BUFEXTCLK << 11) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DIGEXTCLK (_CMU_CTRL_LFXOMODE_DIGEXTCLK << 11) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST (0x1UL << 13) /**< LFXO Start-up Boost Current */
-#define _CMU_CTRL_LFXOBOOST_SHIFT 13 /**< Shift value for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_MASK 0x2000UL /**< Bit mask for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_70PCENT 0x00000000UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_100PCENT 0x00000001UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_70PCENT (_CMU_CTRL_LFXOBOOST_70PCENT << 13) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_DEFAULT (_CMU_CTRL_LFXOBOOST_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_100PCENT (_CMU_CTRL_LFXOBOOST_100PCENT << 13) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR (0x1UL << 17) /**< LFXO Boost Buffer Current */
-#define _CMU_CTRL_LFXOBUFCUR_SHIFT 17 /**< Shift value for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_MASK 0x20000UL /**< Bit mask for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR_DEFAULT (_CMU_CTRL_LFXOBUFCUR_DEFAULT << 17) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_SHIFT 18 /**< Shift value for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_MASK 0xC0000UL /**< Bit mask for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_1KCYCLES 0x00000001UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_16KCYCLES 0x00000002UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_32KCYCLES 0x00000003UL /**< Mode 32KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_8CYCLES (_CMU_CTRL_LFXOTIMEOUT_8CYCLES << 18) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_1KCYCLES (_CMU_CTRL_LFXOTIMEOUT_1KCYCLES << 18) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_16KCYCLES (_CMU_CTRL_LFXOTIMEOUT_16KCYCLES << 18) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_DEFAULT (_CMU_CTRL_LFXOTIMEOUT_DEFAULT << 18) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_32KCYCLES (_CMU_CTRL_LFXOTIMEOUT_32KCYCLES << 18) /**< Shifted mode 32KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_SHIFT 20 /**< Shift value for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_MASK 0x700000UL /**< Bit mask for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFRCO 0x00000000UL /**< Mode HFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFXO 0x00000001UL /**< Mode HFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK2 0x00000002UL /**< Mode HFCLK2 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK4 0x00000003UL /**< Mode HFCLK4 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK8 0x00000004UL /**< Mode HFCLK8 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK16 0x00000005UL /**< Mode HFCLK16 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_ULFRCO 0x00000006UL /**< Mode ULFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_AUXHFRCO 0x00000007UL /**< Mode AUXHFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_DEFAULT (_CMU_CTRL_CLKOUTSEL0_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFRCO (_CMU_CTRL_CLKOUTSEL0_HFRCO << 20) /**< Shifted mode HFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFXO (_CMU_CTRL_CLKOUTSEL0_HFXO << 20) /**< Shifted mode HFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK2 (_CMU_CTRL_CLKOUTSEL0_HFCLK2 << 20) /**< Shifted mode HFCLK2 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK4 (_CMU_CTRL_CLKOUTSEL0_HFCLK4 << 20) /**< Shifted mode HFCLK4 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK8 (_CMU_CTRL_CLKOUTSEL0_HFCLK8 << 20) /**< Shifted mode HFCLK8 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK16 (_CMU_CTRL_CLKOUTSEL0_HFCLK16 << 20) /**< Shifted mode HFCLK16 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_ULFRCO (_CMU_CTRL_CLKOUTSEL0_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_AUXHFRCO (_CMU_CTRL_CLKOUTSEL0_AUXHFRCO << 20) /**< Shifted mode AUXHFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_SHIFT 23 /**< Shift value for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_MASK 0x7800000UL /**< Bit mask for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCO 0x00000000UL /**< Mode LFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXO 0x00000001UL /**< Mode LFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFCLK 0x00000002UL /**< Mode HFCLK for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXOQ 0x00000003UL /**< Mode LFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFXOQ 0x00000004UL /**< Mode HFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCOQ 0x00000005UL /**< Mode LFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFRCOQ 0x00000006UL /**< Mode HFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ 0x00000007UL /**< Mode AUXHFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_DEFAULT (_CMU_CTRL_CLKOUTSEL1_DEFAULT << 23) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCO (_CMU_CTRL_CLKOUTSEL1_LFRCO << 23) /**< Shifted mode LFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXO (_CMU_CTRL_CLKOUTSEL1_LFXO << 23) /**< Shifted mode LFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFCLK (_CMU_CTRL_CLKOUTSEL1_HFCLK << 23) /**< Shifted mode HFCLK for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXOQ (_CMU_CTRL_CLKOUTSEL1_LFXOQ << 23) /**< Shifted mode LFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFXOQ (_CMU_CTRL_CLKOUTSEL1_HFXOQ << 23) /**< Shifted mode HFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCOQ (_CMU_CTRL_CLKOUTSEL1_LFRCOQ << 23) /**< Shifted mode LFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFRCOQ (_CMU_CTRL_CLKOUTSEL1_HFRCOQ << 23) /**< Shifted mode HFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ (_CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ << 23) /**< Shifted mode AUXHFRCOQ for CMU_CTRL */
-
-/* Bit fields for CMU HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_SHIFT 0 /**< Shift value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV (0x1UL << 8) /**< Additional Division Factor For HFCORECLKLE */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_SHIFT 8 /**< Shift value for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_MASK 0x100UL /**< Bit mask for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 0x00000000UL /**< Mode DIV2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 0x00000001UL /**< Mode DIV4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 << 8) /**< Shifted mode DIV2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 << 8) /**< Shifted mode DIV4 for CMU_HFCORECLKDIV */
-
-/* Bit fields for CMU HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_RESETVALUE 0x00000100UL /**< Default value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_SHIFT 0 /**< Shift value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN (0x1UL << 8) /**< HFPERCLK Enable */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_SHIFT 8 /**< Shift value for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_MASK 0x100UL /**< Bit mask for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-
-/* Bit fields for CMU HFRCOCTRL */
-#define _CMU_HFRCOCTRL_RESETVALUE 0x00000380UL /**< Default value for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_MASK 0x0001F7FFUL /**< Mask for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_TUNING_DEFAULT (_CMU_HFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_1MHZ 0x00000000UL /**< Mode 1MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_7MHZ 0x00000001UL /**< Mode 7MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_11MHZ 0x00000002UL /**< Mode 11MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_14MHZ 0x00000003UL /**< Mode 14MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_21MHZ 0x00000004UL /**< Mode 21MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_1MHZ (_CMU_HFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_7MHZ (_CMU_HFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_11MHZ (_CMU_HFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_DEFAULT (_CMU_HFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_14MHZ (_CMU_HFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_21MHZ (_CMU_HFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_SUDELAY_SHIFT 12 /**< Shift value for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_MASK 0x1F000UL /**< Bit mask for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_SUDELAY_DEFAULT (_CMU_HFRCOCTRL_SUDELAY_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-
-/* Bit fields for CMU LFRCOCTRL */
-#define _CMU_LFRCOCTRL_RESETVALUE 0x00000040UL /**< Default value for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_MASK 0x0000007FUL /**< Mask for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_MASK 0x7FUL /**< Bit mask for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_DEFAULT 0x00000040UL /**< Mode DEFAULT for CMU_LFRCOCTRL */
-#define CMU_LFRCOCTRL_TUNING_DEFAULT (_CMU_LFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFRCOCTRL */
-
-/* Bit fields for CMU AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_RESETVALUE 0x00000080UL /**< Default value for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_MASK 0x000007FFUL /**< Mask for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_TUNING_DEFAULT (_CMU_AUXHFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_14MHZ 0x00000000UL /**< Mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_11MHZ 0x00000001UL /**< Mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_7MHZ 0x00000002UL /**< Mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_1MHZ 0x00000003UL /**< Mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_21MHZ 0x00000007UL /**< Mode 21MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_DEFAULT (_CMU_AUXHFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_14MHZ (_CMU_AUXHFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_11MHZ (_CMU_AUXHFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_7MHZ (_CMU_AUXHFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_1MHZ (_CMU_AUXHFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_21MHZ (_CMU_AUXHFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_AUXHFRCOCTRL */
-
-/* Bit fields for CMU CALCTRL */
-#define _CMU_CALCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCTRL */
-#define _CMU_CALCTRL_MASK 0x0000007FUL /**< Mask for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_SHIFT 0 /**< Shift value for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_MASK 0x7UL /**< Bit mask for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFXO 0x00000000UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFXO 0x00000001UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFRCO 0x00000002UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_AUXHFRCO 0x00000004UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_DEFAULT (_CMU_CALCTRL_UPSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFXO (_CMU_CALCTRL_UPSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFXO (_CMU_CALCTRL_UPSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFRCO (_CMU_CALCTRL_UPSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFRCO (_CMU_CALCTRL_UPSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_AUXHFRCO (_CMU_CALCTRL_UPSEL_AUXHFRCO << 0) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_SHIFT 3 /**< Shift value for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_MASK 0x38UL /**< Bit mask for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFXO 0x00000001UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFXO 0x00000002UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFRCO 0x00000003UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFRCO 0x00000004UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_AUXHFRCO 0x00000005UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_DEFAULT (_CMU_CALCTRL_DOWNSEL_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFCLK (_CMU_CALCTRL_DOWNSEL_HFCLK << 3) /**< Shifted mode HFCLK for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFXO (_CMU_CALCTRL_DOWNSEL_HFXO << 3) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFXO (_CMU_CALCTRL_DOWNSEL_LFXO << 3) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFRCO (_CMU_CALCTRL_DOWNSEL_HFRCO << 3) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFRCO (_CMU_CALCTRL_DOWNSEL_LFRCO << 3) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_AUXHFRCO (_CMU_CALCTRL_DOWNSEL_AUXHFRCO << 3) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT (0x1UL << 6) /**< Continuous Calibration */
-#define _CMU_CALCTRL_CONT_SHIFT 6 /**< Shift value for CMU_CONT */
-#define _CMU_CALCTRL_CONT_MASK 0x40UL /**< Bit mask for CMU_CONT */
-#define _CMU_CALCTRL_CONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT_DEFAULT (_CMU_CALCTRL_CONT_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-
-/* Bit fields for CMU CALCNT */
-#define _CMU_CALCNT_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCNT */
-#define _CMU_CALCNT_MASK 0x000FFFFFUL /**< Mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_SHIFT 0 /**< Shift value for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_MASK 0xFFFFFUL /**< Bit mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCNT */
-#define CMU_CALCNT_CALCNT_DEFAULT (_CMU_CALCNT_CALCNT_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCNT */
-
-/* Bit fields for CMU OSCENCMD */
-#define _CMU_OSCENCMD_RESETVALUE 0x00000000UL /**< Default value for CMU_OSCENCMD */
-#define _CMU_OSCENCMD_MASK 0x000003FFUL /**< Mask for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN (0x1UL << 0) /**< HFRCO Enable */
-#define _CMU_OSCENCMD_HFRCOEN_SHIFT 0 /**< Shift value for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_MASK 0x1UL /**< Bit mask for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN_DEFAULT (_CMU_OSCENCMD_HFRCOEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS (0x1UL << 1) /**< HFRCO Disable */
-#define _CMU_OSCENCMD_HFRCODIS_SHIFT 1 /**< Shift value for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_MASK 0x2UL /**< Bit mask for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS_DEFAULT (_CMU_OSCENCMD_HFRCODIS_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN (0x1UL << 2) /**< HFXO Enable */
-#define _CMU_OSCENCMD_HFXOEN_SHIFT 2 /**< Shift value for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_MASK 0x4UL /**< Bit mask for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN_DEFAULT (_CMU_OSCENCMD_HFXOEN_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS (0x1UL << 3) /**< HFXO Disable */
-#define _CMU_OSCENCMD_HFXODIS_SHIFT 3 /**< Shift value for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_MASK 0x8UL /**< Bit mask for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS_DEFAULT (_CMU_OSCENCMD_HFXODIS_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN (0x1UL << 4) /**< AUXHFRCO Enable */
-#define _CMU_OSCENCMD_AUXHFRCOEN_SHIFT 4 /**< Shift value for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN_DEFAULT (_CMU_OSCENCMD_AUXHFRCOEN_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS (0x1UL << 5) /**< AUXHFRCO Disable */
-#define _CMU_OSCENCMD_AUXHFRCODIS_SHIFT 5 /**< Shift value for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS_DEFAULT (_CMU_OSCENCMD_AUXHFRCODIS_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN (0x1UL << 6) /**< LFRCO Enable */
-#define _CMU_OSCENCMD_LFRCOEN_SHIFT 6 /**< Shift value for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_MASK 0x40UL /**< Bit mask for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN_DEFAULT (_CMU_OSCENCMD_LFRCOEN_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS (0x1UL << 7) /**< LFRCO Disable */
-#define _CMU_OSCENCMD_LFRCODIS_SHIFT 7 /**< Shift value for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_MASK 0x80UL /**< Bit mask for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS_DEFAULT (_CMU_OSCENCMD_LFRCODIS_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN (0x1UL << 8) /**< LFXO Enable */
-#define _CMU_OSCENCMD_LFXOEN_SHIFT 8 /**< Shift value for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_MASK 0x100UL /**< Bit mask for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN_DEFAULT (_CMU_OSCENCMD_LFXOEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS (0x1UL << 9) /**< LFXO Disable */
-#define _CMU_OSCENCMD_LFXODIS_SHIFT 9 /**< Shift value for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_MASK 0x200UL /**< Bit mask for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS_DEFAULT (_CMU_OSCENCMD_LFXODIS_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-
-/* Bit fields for CMU CMD */
-#define _CMU_CMD_RESETVALUE 0x00000000UL /**< Default value for CMU_CMD */
-#define _CMU_CMD_MASK 0x0000001FUL /**< Mask for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_SHIFT 0 /**< Shift value for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_MASK 0x7UL /**< Bit mask for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFRCO 0x00000001UL /**< Mode HFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFXO 0x00000002UL /**< Mode HFXO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFXO 0x00000004UL /**< Mode LFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_DEFAULT (_CMU_CMD_HFCLKSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFRCO (_CMU_CMD_HFCLKSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFXO (_CMU_CMD_HFCLKSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFRCO (_CMU_CMD_HFCLKSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFXO (_CMU_CMD_HFCLKSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CMD */
-#define CMU_CMD_CALSTART (0x1UL << 3) /**< Calibration Start */
-#define _CMU_CMD_CALSTART_SHIFT 3 /**< Shift value for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_MASK 0x8UL /**< Bit mask for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTART_DEFAULT (_CMU_CMD_CALSTART_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP (0x1UL << 4) /**< Calibration Stop */
-#define _CMU_CMD_CALSTOP_SHIFT 4 /**< Shift value for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_MASK 0x10UL /**< Bit mask for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP_DEFAULT (_CMU_CMD_CALSTOP_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_CMD */
-
-/* Bit fields for CMU LFCLKSEL */
-#define _CMU_LFCLKSEL_RESETVALUE 0x00000005UL /**< Default value for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_MASK 0x0011000FUL /**< Mask for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_SHIFT 0 /**< Shift value for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_MASK 0x3UL /**< Bit mask for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DISABLED (_CMU_LFCLKSEL_LFA_DISABLED << 0) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DEFAULT (_CMU_LFCLKSEL_LFA_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFRCO (_CMU_LFCLKSEL_LFA_LFRCO << 0) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFXO (_CMU_LFCLKSEL_LFA_LFXO << 0) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 << 0) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_SHIFT 2 /**< Shift value for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_MASK 0xCUL /**< Bit mask for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DISABLED (_CMU_LFCLKSEL_LFB_DISABLED << 2) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DEFAULT (_CMU_LFCLKSEL_LFB_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFRCO (_CMU_LFCLKSEL_LFB_LFRCO << 2) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFXO (_CMU_LFCLKSEL_LFB_LFXO << 2) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 << 2) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE (0x1UL << 16) /**< Clock Select for LFA Extended */
-#define _CMU_LFCLKSEL_LFAE_SHIFT 16 /**< Shift value for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_MASK 0x10000UL /**< Bit mask for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DEFAULT (_CMU_LFCLKSEL_LFAE_DEFAULT << 16) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DISABLED (_CMU_LFCLKSEL_LFAE_DISABLED << 16) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_ULFRCO (_CMU_LFCLKSEL_LFAE_ULFRCO << 16) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE (0x1UL << 20) /**< Clock Select for LFB Extended */
-#define _CMU_LFCLKSEL_LFBE_SHIFT 20 /**< Shift value for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_MASK 0x100000UL /**< Bit mask for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DEFAULT (_CMU_LFCLKSEL_LFBE_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DISABLED (_CMU_LFCLKSEL_LFBE_DISABLED << 20) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_ULFRCO (_CMU_LFCLKSEL_LFBE_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-
-/* Bit fields for CMU STATUS */
-#define _CMU_STATUS_RESETVALUE 0x00000403UL /**< Default value for CMU_STATUS */
-#define _CMU_STATUS_MASK 0x00007FFFUL /**< Mask for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS (0x1UL << 0) /**< HFRCO Enable Status */
-#define _CMU_STATUS_HFRCOENS_SHIFT 0 /**< Shift value for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_MASK 0x1UL /**< Bit mask for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS_DEFAULT (_CMU_STATUS_HFRCOENS_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY (0x1UL << 1) /**< HFRCO Ready */
-#define _CMU_STATUS_HFRCORDY_SHIFT 1 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_MASK 0x2UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY_DEFAULT (_CMU_STATUS_HFRCORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS (0x1UL << 2) /**< HFXO Enable Status */
-#define _CMU_STATUS_HFXOENS_SHIFT 2 /**< Shift value for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_MASK 0x4UL /**< Bit mask for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS_DEFAULT (_CMU_STATUS_HFXOENS_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY (0x1UL << 3) /**< HFXO Ready */
-#define _CMU_STATUS_HFXORDY_SHIFT 3 /**< Shift value for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_MASK 0x8UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY_DEFAULT (_CMU_STATUS_HFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS (0x1UL << 4) /**< AUXHFRCO Enable Status */
-#define _CMU_STATUS_AUXHFRCOENS_SHIFT 4 /**< Shift value for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS_DEFAULT (_CMU_STATUS_AUXHFRCOENS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY (0x1UL << 5) /**< AUXHFRCO Ready */
-#define _CMU_STATUS_AUXHFRCORDY_SHIFT 5 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY_DEFAULT (_CMU_STATUS_AUXHFRCORDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS (0x1UL << 6) /**< LFRCO Enable Status */
-#define _CMU_STATUS_LFRCOENS_SHIFT 6 /**< Shift value for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_MASK 0x40UL /**< Bit mask for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS_DEFAULT (_CMU_STATUS_LFRCOENS_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY (0x1UL << 7) /**< LFRCO Ready */
-#define _CMU_STATUS_LFRCORDY_SHIFT 7 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_MASK 0x80UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY_DEFAULT (_CMU_STATUS_LFRCORDY_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS (0x1UL << 8) /**< LFXO Enable Status */
-#define _CMU_STATUS_LFXOENS_SHIFT 8 /**< Shift value for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_MASK 0x100UL /**< Bit mask for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS_DEFAULT (_CMU_STATUS_LFXOENS_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY (0x1UL << 9) /**< LFXO Ready */
-#define _CMU_STATUS_LFXORDY_SHIFT 9 /**< Shift value for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_MASK 0x200UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY_DEFAULT (_CMU_STATUS_LFXORDY_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL (0x1UL << 10) /**< HFRCO Selected */
-#define _CMU_STATUS_HFRCOSEL_SHIFT 10 /**< Shift value for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_MASK 0x400UL /**< Bit mask for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL_DEFAULT (_CMU_STATUS_HFRCOSEL_DEFAULT << 10) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL (0x1UL << 11) /**< HFXO Selected */
-#define _CMU_STATUS_HFXOSEL_SHIFT 11 /**< Shift value for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_MASK 0x800UL /**< Bit mask for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL_DEFAULT (_CMU_STATUS_HFXOSEL_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL (0x1UL << 12) /**< LFRCO Selected */
-#define _CMU_STATUS_LFRCOSEL_SHIFT 12 /**< Shift value for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_MASK 0x1000UL /**< Bit mask for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL_DEFAULT (_CMU_STATUS_LFRCOSEL_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL (0x1UL << 13) /**< LFXO Selected */
-#define _CMU_STATUS_LFXOSEL_SHIFT 13 /**< Shift value for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_MASK 0x2000UL /**< Bit mask for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL_DEFAULT (_CMU_STATUS_LFXOSEL_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY (0x1UL << 14) /**< Calibration Busy */
-#define _CMU_STATUS_CALBSY_SHIFT 14 /**< Shift value for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_MASK 0x4000UL /**< Bit mask for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY_DEFAULT (_CMU_STATUS_CALBSY_DEFAULT << 14) /**< Shifted mode DEFAULT for CMU_STATUS */
-
-/* Bit fields for CMU IF */
-#define _CMU_IF_RESETVALUE 0x00000001UL /**< Default value for CMU_IF */
-#define _CMU_IF_MASK 0x0000007FUL /**< Mask for CMU_IF */
-#define CMU_IF_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag */
-#define _CMU_IF_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFRCORDY_DEFAULT (_CMU_IF_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag */
-#define _CMU_IF_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY_DEFAULT (_CMU_IF_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag */
-#define _CMU_IF_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY_DEFAULT (_CMU_IF_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag */
-#define _CMU_IF_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY_DEFAULT (_CMU_IF_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag */
-#define _CMU_IF_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY_DEFAULT (_CMU_IF_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag */
-#define _CMU_IF_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IF_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IF_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY_DEFAULT (_CMU_IF_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag */
-#define _CMU_IF_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IF_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IF_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF_DEFAULT (_CMU_IF_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IF */
-
-/* Bit fields for CMU IFS */
-#define _CMU_IFS_RESETVALUE 0x00000000UL /**< Default value for CMU_IFS */
-#define _CMU_IFS_MASK 0x0000007FUL /**< Mask for CMU_IFS */
-#define CMU_IFS_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFRCORDY_DEFAULT (_CMU_IFS_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY_DEFAULT (_CMU_IFS_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY_DEFAULT (_CMU_IFS_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY_DEFAULT (_CMU_IFS_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY_DEFAULT (_CMU_IFS_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Set */
-#define _CMU_IFS_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY_DEFAULT (_CMU_IFS_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Set */
-#define _CMU_IFS_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFS_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFS_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF_DEFAULT (_CMU_IFS_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFS */
-
-/* Bit fields for CMU IFC */
-#define _CMU_IFC_RESETVALUE 0x00000000UL /**< Default value for CMU_IFC */
-#define _CMU_IFC_MASK 0x0000007FUL /**< Mask for CMU_IFC */
-#define CMU_IFC_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFRCORDY_DEFAULT (_CMU_IFC_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY_DEFAULT (_CMU_IFC_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY_DEFAULT (_CMU_IFC_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY_DEFAULT (_CMU_IFC_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY_DEFAULT (_CMU_IFC_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Clear */
-#define _CMU_IFC_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY_DEFAULT (_CMU_IFC_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Clear */
-#define _CMU_IFC_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFC_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFC_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF_DEFAULT (_CMU_IFC_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFC */
-
-/* Bit fields for CMU IEN */
-#define _CMU_IEN_RESETVALUE 0x00000000UL /**< Default value for CMU_IEN */
-#define _CMU_IEN_MASK 0x0000007FUL /**< Mask for CMU_IEN */
-#define CMU_IEN_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Enable */
-#define _CMU_IEN_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFRCORDY_DEFAULT (_CMU_IEN_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Enable */
-#define _CMU_IEN_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY_DEFAULT (_CMU_IEN_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Enable */
-#define _CMU_IEN_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY_DEFAULT (_CMU_IEN_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Enable */
-#define _CMU_IEN_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY_DEFAULT (_CMU_IEN_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Enable */
-#define _CMU_IEN_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY_DEFAULT (_CMU_IEN_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Enable */
-#define _CMU_IEN_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY_DEFAULT (_CMU_IEN_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Enable */
-#define _CMU_IEN_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IEN_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IEN_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF_DEFAULT (_CMU_IEN_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IEN */
-
-/* Bit fields for CMU HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_MASK 0x00000006UL /**< Mask for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA (0x1UL << 1) /**< Direct Memory Access Controller Clock Enable */
-#define _CMU_HFCORECLKEN0_DMA_SHIFT 1 /**< Shift value for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_MASK 0x2UL /**< Bit mask for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA_DEFAULT (_CMU_HFCORECLKEN0_DMA_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE (0x1UL << 2) /**< Low Energy Peripheral Interface Clock Enable */
-#define _CMU_HFCORECLKEN0_LE_SHIFT 2 /**< Shift value for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_MASK 0x4UL /**< Bit mask for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE_DEFAULT (_CMU_HFCORECLKEN0_LE_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-
-/* Bit fields for CMU HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_MASK 0x0000099FUL /**< Mask for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0 (0x1UL << 0) /**< Timer 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER0_SHIFT 0 /**< Shift value for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_MASK 0x1UL /**< Bit mask for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0_DEFAULT (_CMU_HFPERCLKEN0_TIMER0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1 (0x1UL << 1) /**< Timer 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER1_SHIFT 1 /**< Shift value for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_MASK 0x2UL /**< Bit mask for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1_DEFAULT (_CMU_HFPERCLKEN0_TIMER1_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0 (0x1UL << 2) /**< Analog Comparator 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_ACMP0_SHIFT 2 /**< Shift value for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_MASK 0x4UL /**< Bit mask for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0_DEFAULT (_CMU_HFPERCLKEN0_ACMP0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1 (0x1UL << 3) /**< Universal Synchronous/Asynchronous Receiver/Transmitter 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_USART1_SHIFT 3 /**< Shift value for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_MASK 0x8UL /**< Bit mask for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1_DEFAULT (_CMU_HFPERCLKEN0_USART1_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS (0x1UL << 4) /**< Peripheral Reflex System Clock Enable */
-#define _CMU_HFPERCLKEN0_PRS_SHIFT 4 /**< Shift value for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_MASK 0x10UL /**< Bit mask for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS_DEFAULT (_CMU_HFPERCLKEN0_PRS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO (0x1UL << 7) /**< General purpose Input/Output Clock Enable */
-#define _CMU_HFPERCLKEN0_GPIO_SHIFT 7 /**< Shift value for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_MASK 0x80UL /**< Bit mask for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO_DEFAULT (_CMU_HFPERCLKEN0_GPIO_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP (0x1UL << 8) /**< Voltage Comparator Clock Enable */
-#define _CMU_HFPERCLKEN0_VCMP_SHIFT 8 /**< Shift value for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_MASK 0x100UL /**< Bit mask for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP_DEFAULT (_CMU_HFPERCLKEN0_VCMP_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0 (0x1UL << 11) /**< I2C 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_I2C0_SHIFT 11 /**< Shift value for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_MASK 0x800UL /**< Bit mask for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0_DEFAULT (_CMU_HFPERCLKEN0_I2C0_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-
-/* Bit fields for CMU SYNCBUSY */
-#define _CMU_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for CMU_SYNCBUSY */
-#define _CMU_SYNCBUSY_MASK 0x00000055UL /**< Mask for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0 (0x1UL << 0) /**< Low Frequency A Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFACLKEN0_SHIFT 0 /**< Shift value for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_MASK 0x1UL /**< Bit mask for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0_DEFAULT (_CMU_SYNCBUSY_LFACLKEN0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0 (0x1UL << 2) /**< Low Frequency A Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFAPRESC0_SHIFT 2 /**< Shift value for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_MASK 0x4UL /**< Bit mask for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0_DEFAULT (_CMU_SYNCBUSY_LFAPRESC0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0 (0x1UL << 4) /**< Low Frequency B Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFBCLKEN0_SHIFT 4 /**< Shift value for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_MASK 0x10UL /**< Bit mask for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0_DEFAULT (_CMU_SYNCBUSY_LFBCLKEN0_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0 (0x1UL << 6) /**< Low Frequency B Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFBPRESC0_SHIFT 6 /**< Shift value for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_MASK 0x40UL /**< Bit mask for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0_DEFAULT (_CMU_SYNCBUSY_LFBPRESC0_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-
-/* Bit fields for CMU FREEZE */
-#define _CMU_FREEZE_RESETVALUE 0x00000000UL /**< Default value for CMU_FREEZE */
-#define _CMU_FREEZE_MASK 0x00000001UL /**< Mask for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _CMU_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_DEFAULT (_CMU_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_UPDATE (_CMU_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_FREEZE (_CMU_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for CMU_FREEZE */
-
-/* Bit fields for CMU LFACLKEN0 */
-#define _CMU_LFACLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFACLKEN0 */
-#define _CMU_LFACLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC (0x1UL << 0) /**< Real-Time Counter Clock Enable */
-#define _CMU_LFACLKEN0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_MASK 0x1UL /**< Bit mask for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC_DEFAULT (_CMU_LFACLKEN0_RTC_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFACLKEN0 */
-
-/* Bit fields for CMU LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0 (0x1UL << 0) /**< Low Energy UART 0 Clock Enable */
-#define _CMU_LFBCLKEN0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_MASK 0x1UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0_DEFAULT (_CMU_LFBCLKEN0_LEUART0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFBCLKEN0 */
-
-/* Bit fields for CMU LFAPRESC0 */
-#define _CMU_LFAPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_MASK 0x0000000FUL /**< Mask for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_MASK 0xFUL /**< Bit mask for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16 0x00000004UL /**< Mode DIV16 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32 0x00000005UL /**< Mode DIV32 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV64 0x00000006UL /**< Mode DIV64 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV128 0x00000007UL /**< Mode DIV128 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV256 0x00000008UL /**< Mode DIV256 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV512 0x00000009UL /**< Mode DIV512 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV1024 0x0000000AUL /**< Mode DIV1024 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2048 0x0000000BUL /**< Mode DIV2048 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4096 0x0000000CUL /**< Mode DIV4096 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8192 0x0000000DUL /**< Mode DIV8192 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16384 0x0000000EUL /**< Mode DIV16384 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32768 0x0000000FUL /**< Mode DIV32768 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1 (_CMU_LFAPRESC0_RTC_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2 (_CMU_LFAPRESC0_RTC_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4 (_CMU_LFAPRESC0_RTC_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8 (_CMU_LFAPRESC0_RTC_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16 (_CMU_LFAPRESC0_RTC_DIV16 << 0) /**< Shifted mode DIV16 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32 (_CMU_LFAPRESC0_RTC_DIV32 << 0) /**< Shifted mode DIV32 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV64 (_CMU_LFAPRESC0_RTC_DIV64 << 0) /**< Shifted mode DIV64 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV128 (_CMU_LFAPRESC0_RTC_DIV128 << 0) /**< Shifted mode DIV128 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV256 (_CMU_LFAPRESC0_RTC_DIV256 << 0) /**< Shifted mode DIV256 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV512 (_CMU_LFAPRESC0_RTC_DIV512 << 0) /**< Shifted mode DIV512 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1024 (_CMU_LFAPRESC0_RTC_DIV1024 << 0) /**< Shifted mode DIV1024 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2048 (_CMU_LFAPRESC0_RTC_DIV2048 << 0) /**< Shifted mode DIV2048 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4096 (_CMU_LFAPRESC0_RTC_DIV4096 << 0) /**< Shifted mode DIV4096 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8192 (_CMU_LFAPRESC0_RTC_DIV8192 << 0) /**< Shifted mode DIV8192 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16384 (_CMU_LFAPRESC0_RTC_DIV16384 << 0) /**< Shifted mode DIV16384 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32768 (_CMU_LFAPRESC0_RTC_DIV32768 << 0) /**< Shifted mode DIV32768 for CMU_LFAPRESC0 */
-
-/* Bit fields for CMU LFBPRESC0 */
-#define _CMU_LFBPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_MASK 0x00000003UL /**< Mask for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_MASK 0x3UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV1 (_CMU_LFBPRESC0_LEUART0_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV2 (_CMU_LFBPRESC0_LEUART0_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV4 (_CMU_LFBPRESC0_LEUART0_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV8 (_CMU_LFBPRESC0_LEUART0_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFBPRESC0 */
-
-/* Bit fields for CMU PCNTCTRL */
-#define _CMU_PCNTCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_MASK 0x00000003UL /**< Mask for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN (0x1UL << 0) /**< PCNT0 Clock Enable */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_SHIFT 0 /**< Shift value for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_MASK 0x1UL /**< Bit mask for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL (0x1UL << 1) /**< PCNT0 Clock Select */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_SHIFT 1 /**< Shift value for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_MASK 0x2UL /**< Bit mask for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK 0x00000000UL /**< Mode LFACLK for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 0x00000001UL /**< Mode PCNT0S0 for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK (_CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK << 1) /**< Shifted mode LFACLK for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 (_CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 << 1) /**< Shifted mode PCNT0S0 for CMU_PCNTCTRL */
-
-/* Bit fields for CMU ROUTE */
-#define _CMU_ROUTE_RESETVALUE 0x00000000UL /**< Default value for CMU_ROUTE */
-#define _CMU_ROUTE_MASK 0x0000001FUL /**< Mask for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN (0x1UL << 0) /**< CLKOUT0 Pin Enable */
-#define _CMU_ROUTE_CLKOUT0PEN_SHIFT 0 /**< Shift value for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_MASK 0x1UL /**< Bit mask for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN_DEFAULT (_CMU_ROUTE_CLKOUT0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN (0x1UL << 1) /**< CLKOUT1 Pin Enable */
-#define _CMU_ROUTE_CLKOUT1PEN_SHIFT 1 /**< Shift value for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_MASK 0x2UL /**< Bit mask for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN_DEFAULT (_CMU_ROUTE_CLKOUT1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_SHIFT 2 /**< Shift value for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_MASK 0x1CUL /**< Bit mask for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC0 (_CMU_ROUTE_LOCATION_LOC0 << 2) /**< Shifted mode LOC0 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_DEFAULT (_CMU_ROUTE_LOCATION_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC1 (_CMU_ROUTE_LOCATION_LOC1 << 2) /**< Shifted mode LOC1 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC2 (_CMU_ROUTE_LOCATION_LOC2 << 2) /**< Shifted mode LOC2 for CMU_ROUTE */
-
-/* Bit fields for CMU LOCK */
-#define _CMU_LOCK_RESETVALUE 0x00000000UL /**< Default value for CMU_LOCK */
-#define _CMU_LOCK_MASK 0x0000FFFFUL /**< Mask for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCK 0x0000580EUL /**< Mode UNLOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_DEFAULT (_CMU_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCK (_CMU_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCKED (_CMU_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCKED (_CMU_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCK (_CMU_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for CMU_LOCK */
-
-/** @} End of group EFM32ZG108F4_CMU */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_PRS_BitFields EFM32ZG108F4_PRS Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for PRS SWPULSE */
-#define _PRS_SWPULSE_RESETVALUE 0x00000000UL /**< Default value for PRS_SWPULSE */
-#define _PRS_SWPULSE_MASK 0x0000000FUL /**< Mask for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE (0x1UL << 0) /**< Channel 0 Pulse Generation */
-#define _PRS_SWPULSE_CH0PULSE_SHIFT 0 /**< Shift value for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_MASK 0x1UL /**< Bit mask for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE_DEFAULT (_PRS_SWPULSE_CH0PULSE_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE (0x1UL << 1) /**< Channel 1 Pulse Generation */
-#define _PRS_SWPULSE_CH1PULSE_SHIFT 1 /**< Shift value for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_MASK 0x2UL /**< Bit mask for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE_DEFAULT (_PRS_SWPULSE_CH1PULSE_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE (0x1UL << 2) /**< Channel 2 Pulse Generation */
-#define _PRS_SWPULSE_CH2PULSE_SHIFT 2 /**< Shift value for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_MASK 0x4UL /**< Bit mask for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE_DEFAULT (_PRS_SWPULSE_CH2PULSE_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE (0x1UL << 3) /**< Channel 3 Pulse Generation */
-#define _PRS_SWPULSE_CH3PULSE_SHIFT 3 /**< Shift value for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_MASK 0x8UL /**< Bit mask for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE_DEFAULT (_PRS_SWPULSE_CH3PULSE_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-
-/* Bit fields for PRS SWLEVEL */
-#define _PRS_SWLEVEL_RESETVALUE 0x00000000UL /**< Default value for PRS_SWLEVEL */
-#define _PRS_SWLEVEL_MASK 0x0000000FUL /**< Mask for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL (0x1UL << 0) /**< Channel 0 Software Level */
-#define _PRS_SWLEVEL_CH0LEVEL_SHIFT 0 /**< Shift value for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_MASK 0x1UL /**< Bit mask for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL_DEFAULT (_PRS_SWLEVEL_CH0LEVEL_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL (0x1UL << 1) /**< Channel 1 Software Level */
-#define _PRS_SWLEVEL_CH1LEVEL_SHIFT 1 /**< Shift value for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_MASK 0x2UL /**< Bit mask for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL_DEFAULT (_PRS_SWLEVEL_CH1LEVEL_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL (0x1UL << 2) /**< Channel 2 Software Level */
-#define _PRS_SWLEVEL_CH2LEVEL_SHIFT 2 /**< Shift value for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_MASK 0x4UL /**< Bit mask for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL_DEFAULT (_PRS_SWLEVEL_CH2LEVEL_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL (0x1UL << 3) /**< Channel 3 Software Level */
-#define _PRS_SWLEVEL_CH3LEVEL_SHIFT 3 /**< Shift value for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_MASK 0x8UL /**< Bit mask for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL_DEFAULT (_PRS_SWLEVEL_CH3LEVEL_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-
-/* Bit fields for PRS ROUTE */
-#define _PRS_ROUTE_RESETVALUE 0x00000000UL /**< Default value for PRS_ROUTE */
-#define _PRS_ROUTE_MASK 0x0000070FUL /**< Mask for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN (0x1UL << 0) /**< CH0 Pin Enable */
-#define _PRS_ROUTE_CH0PEN_SHIFT 0 /**< Shift value for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_MASK 0x1UL /**< Bit mask for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN_DEFAULT (_PRS_ROUTE_CH0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN (0x1UL << 1) /**< CH1 Pin Enable */
-#define _PRS_ROUTE_CH1PEN_SHIFT 1 /**< Shift value for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_MASK 0x2UL /**< Bit mask for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN_DEFAULT (_PRS_ROUTE_CH1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN (0x1UL << 2) /**< CH2 Pin Enable */
-#define _PRS_ROUTE_CH2PEN_SHIFT 2 /**< Shift value for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_MASK 0x4UL /**< Bit mask for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN_DEFAULT (_PRS_ROUTE_CH2PEN_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN (0x1UL << 3) /**< CH3 Pin Enable */
-#define _PRS_ROUTE_CH3PEN_SHIFT 3 /**< Shift value for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_MASK 0x8UL /**< Bit mask for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN_DEFAULT (_PRS_ROUTE_CH3PEN_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_SHIFT 8 /**< Shift value for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC0 (_PRS_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_DEFAULT (_PRS_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC1 (_PRS_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC2 (_PRS_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for PRS_ROUTE */
-
-/* Bit fields for PRS CH_CTRL */
-#define _PRS_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_MASK 0x133F0007UL /**< Mask for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_MASK 0x7UL /**< Bit mask for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_VCMPOUT 0x00000000UL /**< Mode VCMPOUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ACMP0OUT 0x00000000UL /**< Mode ACMP0OUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1IRTX 0x00000000UL /**< Mode USART1IRTX for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0UF 0x00000000UL /**< Mode TIMER0UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1UF 0x00000000UL /**< Mode TIMER1UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCOF 0x00000000UL /**< Mode RTCOF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN0 0x00000000UL /**< Mode GPIOPIN0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN8 0x00000000UL /**< Mode GPIOPIN8 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_PCNT0TCC 0x00000000UL /**< Mode PCNT0TCC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1TXC 0x00000001UL /**< Mode USART1TXC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0OF 0x00000001UL /**< Mode TIMER0OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1OF 0x00000001UL /**< Mode TIMER1OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP0 0x00000001UL /**< Mode RTCCOMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN1 0x00000001UL /**< Mode GPIOPIN1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN9 0x00000001UL /**< Mode GPIOPIN9 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000002UL /**< Mode USART1RXDATAV for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC0 0x00000002UL /**< Mode TIMER0CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC0 0x00000002UL /**< Mode TIMER1CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP1 0x00000002UL /**< Mode RTCCOMP1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN2 0x00000002UL /**< Mode GPIOPIN2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN10 0x00000002UL /**< Mode GPIOPIN10 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC1 0x00000003UL /**< Mode TIMER0CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC1 0x00000003UL /**< Mode TIMER1CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN3 0x00000003UL /**< Mode GPIOPIN3 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN11 0x00000003UL /**< Mode GPIOPIN11 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC2 0x00000004UL /**< Mode TIMER0CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC2 0x00000004UL /**< Mode TIMER1CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN4 0x00000004UL /**< Mode GPIOPIN4 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN12 0x00000004UL /**< Mode GPIOPIN12 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN5 0x00000005UL /**< Mode GPIOPIN5 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN13 0x00000005UL /**< Mode GPIOPIN13 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN6 0x00000006UL /**< Mode GPIOPIN6 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN14 0x00000006UL /**< Mode GPIOPIN14 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN7 0x00000007UL /**< Mode GPIOPIN7 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN15 0x00000007UL /**< Mode GPIOPIN15 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_VCMPOUT (_PRS_CH_CTRL_SIGSEL_VCMPOUT << 0) /**< Shifted mode VCMPOUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ACMP0OUT (_PRS_CH_CTRL_SIGSEL_ACMP0OUT << 0) /**< Shifted mode ACMP0OUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1IRTX (_PRS_CH_CTRL_SIGSEL_USART1IRTX << 0) /**< Shifted mode USART1IRTX for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0UF (_PRS_CH_CTRL_SIGSEL_TIMER0UF << 0) /**< Shifted mode TIMER0UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1UF (_PRS_CH_CTRL_SIGSEL_TIMER1UF << 0) /**< Shifted mode TIMER1UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCOF (_PRS_CH_CTRL_SIGSEL_RTCOF << 0) /**< Shifted mode RTCOF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN0 (_PRS_CH_CTRL_SIGSEL_GPIOPIN0 << 0) /**< Shifted mode GPIOPIN0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN8 (_PRS_CH_CTRL_SIGSEL_GPIOPIN8 << 0) /**< Shifted mode GPIOPIN8 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_PCNT0TCC (_PRS_CH_CTRL_SIGSEL_PCNT0TCC << 0) /**< Shifted mode PCNT0TCC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1TXC (_PRS_CH_CTRL_SIGSEL_USART1TXC << 0) /**< Shifted mode USART1TXC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0OF (_PRS_CH_CTRL_SIGSEL_TIMER0OF << 0) /**< Shifted mode TIMER0OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1OF (_PRS_CH_CTRL_SIGSEL_TIMER1OF << 0) /**< Shifted mode TIMER1OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP0 (_PRS_CH_CTRL_SIGSEL_RTCCOMP0 << 0) /**< Shifted mode RTCCOMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN1 (_PRS_CH_CTRL_SIGSEL_GPIOPIN1 << 0) /**< Shifted mode GPIOPIN1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN9 (_PRS_CH_CTRL_SIGSEL_GPIOPIN9 << 0) /**< Shifted mode GPIOPIN9 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1RXDATAV (_PRS_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC0 (_PRS_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC0 (_PRS_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP1 (_PRS_CH_CTRL_SIGSEL_RTCCOMP1 << 0) /**< Shifted mode RTCCOMP1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN2 (_PRS_CH_CTRL_SIGSEL_GPIOPIN2 << 0) /**< Shifted mode GPIOPIN2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN10 (_PRS_CH_CTRL_SIGSEL_GPIOPIN10 << 0) /**< Shifted mode GPIOPIN10 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC1 (_PRS_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC1 (_PRS_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN3 (_PRS_CH_CTRL_SIGSEL_GPIOPIN3 << 0) /**< Shifted mode GPIOPIN3 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN11 (_PRS_CH_CTRL_SIGSEL_GPIOPIN11 << 0) /**< Shifted mode GPIOPIN11 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC2 (_PRS_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC2 (_PRS_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN4 (_PRS_CH_CTRL_SIGSEL_GPIOPIN4 << 0) /**< Shifted mode GPIOPIN4 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN12 (_PRS_CH_CTRL_SIGSEL_GPIOPIN12 << 0) /**< Shifted mode GPIOPIN12 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN5 (_PRS_CH_CTRL_SIGSEL_GPIOPIN5 << 0) /**< Shifted mode GPIOPIN5 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN13 (_PRS_CH_CTRL_SIGSEL_GPIOPIN13 << 0) /**< Shifted mode GPIOPIN13 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN6 (_PRS_CH_CTRL_SIGSEL_GPIOPIN6 << 0) /**< Shifted mode GPIOPIN6 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN14 (_PRS_CH_CTRL_SIGSEL_GPIOPIN14 << 0) /**< Shifted mode GPIOPIN14 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN7 (_PRS_CH_CTRL_SIGSEL_GPIOPIN7 << 0) /**< Shifted mode GPIOPIN7 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN15 (_PRS_CH_CTRL_SIGSEL_GPIOPIN15 << 0) /**< Shifted mode GPIOPIN15 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_VCMP 0x00000001UL /**< Mode VCMP for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_ACMP0 0x00000002UL /**< Mode ACMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_USART1 0x00000011UL /**< Mode USART1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER0 0x0000001CUL /**< Mode TIMER0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER1 0x0000001DUL /**< Mode TIMER1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_RTC 0x00000028UL /**< Mode RTC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOL 0x00000030UL /**< Mode GPIOL for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOH 0x00000031UL /**< Mode GPIOH for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_PCNT0 0x00000036UL /**< Mode PCNT0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_NONE (_PRS_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_VCMP (_PRS_CH_CTRL_SOURCESEL_VCMP << 16) /**< Shifted mode VCMP for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_ACMP0 (_PRS_CH_CTRL_SOURCESEL_ACMP0 << 16) /**< Shifted mode ACMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_USART1 (_PRS_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER0 (_PRS_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER1 (_PRS_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_RTC (_PRS_CH_CTRL_SOURCESEL_RTC << 16) /**< Shifted mode RTC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOL (_PRS_CH_CTRL_SOURCESEL_GPIOL << 16) /**< Shifted mode GPIOL for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOH (_PRS_CH_CTRL_SOURCESEL_GPIOH << 16) /**< Shifted mode GPIOH for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_PCNT0 (_PRS_CH_CTRL_SOURCESEL_PCNT0 << 16) /**< Shifted mode PCNT0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_SHIFT 24 /**< Shift value for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_MASK 0x3000000UL /**< Bit mask for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_OFF 0x00000000UL /**< Mode OFF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_POSEDGE 0x00000001UL /**< Mode POSEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_NEGEDGE 0x00000002UL /**< Mode NEGEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_BOTHEDGES 0x00000003UL /**< Mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_DEFAULT (_PRS_CH_CTRL_EDSEL_DEFAULT << 24) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_OFF (_PRS_CH_CTRL_EDSEL_OFF << 24) /**< Shifted mode OFF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_POSEDGE (_PRS_CH_CTRL_EDSEL_POSEDGE << 24) /**< Shifted mode POSEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_NEGEDGE (_PRS_CH_CTRL_EDSEL_NEGEDGE << 24) /**< Shifted mode NEGEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_BOTHEDGES (_PRS_CH_CTRL_EDSEL_BOTHEDGES << 24) /**< Shifted mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC (0x1UL << 28) /**< Asynchronous reflex */
-#define _PRS_CH_CTRL_ASYNC_SHIFT 28 /**< Shift value for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_MASK 0x10000000UL /**< Bit mask for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC_DEFAULT (_PRS_CH_CTRL_ASYNC_DEFAULT << 28) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-
-/** @} End of group EFM32ZG108F4_PRS */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_UNLOCK EFM32ZG108F4 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG108F4_UNLOCK */
-
-/** @} End of group EFM32ZG108F4_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F4_Alternate_Function EFM32ZG108F4 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG108F4_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG108F4 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG108F4_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f8.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f8.h
deleted file mode 100644
index c4fd386b93..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg108f8.h
+++ /dev/null
@@ -1,2188 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG108F8
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG108F8_H
-#define EFM32ZG108F8_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8 EFM32ZG108F8
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_Core EFM32ZG108F8 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG108F8_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG108F8_Part EFM32ZG108F8 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG108F8)
-#define EFM32ZG108F8 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG108F8" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG108F8 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00002000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG108F8_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_Peripheral_TypeDefs EFM32ZG108F8 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_dma_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_DMA EFM32ZG108F8 DMA
- * @{
- * @brief EFM32ZG108F8_DMA Register Declaration
- ******************************************************************************/
-typedef struct {
- __IM uint32_t STATUS; /**< DMA Status Registers */
- __OM uint32_t CONFIG; /**< DMA Configuration Register */
- __IOM uint32_t CTRLBASE; /**< Channel Control Data Base Pointer Register */
- __IM uint32_t ALTCTRLBASE; /**< Channel Alternate Control Data Base Pointer Register */
- __IM uint32_t CHWAITSTATUS; /**< Channel Wait on Request Status Register */
- __OM uint32_t CHSWREQ; /**< Channel Software Request Register */
- __IOM uint32_t CHUSEBURSTS; /**< Channel Useburst Set Register */
- __OM uint32_t CHUSEBURSTC; /**< Channel Useburst Clear Register */
- __IOM uint32_t CHREQMASKS; /**< Channel Request Mask Set Register */
- __OM uint32_t CHREQMASKC; /**< Channel Request Mask Clear Register */
- __IOM uint32_t CHENS; /**< Channel Enable Set Register */
- __OM uint32_t CHENC; /**< Channel Enable Clear Register */
- __IOM uint32_t CHALTS; /**< Channel Alternate Set Register */
- __OM uint32_t CHALTC; /**< Channel Alternate Clear Register */
- __IOM uint32_t CHPRIS; /**< Channel Priority Set Register */
- __OM uint32_t CHPRIC; /**< Channel Priority Clear Register */
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t ERRORC; /**< Bus Error Clear Register */
-
- uint32_t RESERVED1[880U]; /**< Reserved for future use **/
- __IM uint32_t CHREQSTATUS; /**< Channel Request Status */
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IM uint32_t CHSREQSTATUS; /**< Channel Single Request Status */
-
- uint32_t RESERVED3[121U]; /**< Reserved for future use **/
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable register */
-
- uint32_t RESERVED4[60U]; /**< Reserved registers */
- DMA_CH_TypeDef CH[4U]; /**< Channel registers */
-} DMA_TypeDef; /** DMA Register Declaration *//** @} */
-
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_CMU EFM32ZG108F8 CMU
- * @{
- * @brief EFM32ZG108F8_CMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< CMU Control Register */
- __IOM uint32_t HFCORECLKDIV; /**< High Frequency Core Clock Division Register */
- __IOM uint32_t HFPERCLKDIV; /**< High Frequency Peripheral Clock Division Register */
- __IOM uint32_t HFRCOCTRL; /**< HFRCO Control Register */
- __IOM uint32_t LFRCOCTRL; /**< LFRCO Control Register */
- __IOM uint32_t AUXHFRCOCTRL; /**< AUXHFRCO Control Register */
- __IOM uint32_t CALCTRL; /**< Calibration Control Register */
- __IOM uint32_t CALCNT; /**< Calibration Counter Register */
- __IOM uint32_t OSCENCMD; /**< Oscillator Enable/Disable Command Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IOM uint32_t LFCLKSEL; /**< Low Frequency Clock Select Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t HFCORECLKEN0; /**< High Frequency Core Clock Enable Register 0 */
- __IOM uint32_t HFPERCLKEN0; /**< High Frequency Peripheral Clock Enable Register 0 */
- uint32_t RESERVED0[2U]; /**< Reserved for future use **/
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IOM uint32_t LFACLKEN0; /**< Low Frequency A Clock Enable Register 0 (Async Reg) */
- uint32_t RESERVED1[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBCLKEN0; /**< Low Frequency B Clock Enable Register 0 (Async Reg) */
-
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFAPRESC0; /**< Low Frequency A Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED3[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBPRESC0; /**< Low Frequency B Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED4[1U]; /**< Reserved for future use **/
- __IOM uint32_t PCNTCTRL; /**< PCNT Control Register */
-
- uint32_t RESERVED5[1U]; /**< Reserved for future use **/
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
-} CMU_TypeDef; /** CMU Register Declaration *//** @} */
-
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_PRS EFM32ZG108F8 PRS
- * @{
- * @brief EFM32ZG108F8_PRS Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t SWPULSE; /**< Software Pulse Register */
- __IOM uint32_t SWLEVEL; /**< Software Level Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved registers */
- PRS_CH_TypeDef CH[4U]; /**< Channel registers */
-} PRS_TypeDef; /** PRS Register Declaration *//** @} */
-
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG108F8_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_Peripheral_Base EFM32ZG108F8 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG108F8_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_Peripheral_Declaration EFM32ZG108F8 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG108F8_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_BitFields EFM32ZG108F8 Bit Fields
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @addtogroup EFM32ZG108F8_PRS_Signals
- * @{
- * @brief PRS Signal names
- ******************************************************************************/
-#define PRS_VCMP_OUT ((1 << 16) + 0) /**< PRS Voltage comparator output */
-#define PRS_ACMP0_OUT ((2 << 16) + 0) /**< PRS Analog comparator output */
-#define PRS_USART1_IRTX ((17 << 16) + 0) /**< PRS USART 1 IRDA out */
-#define PRS_USART1_TXC ((17 << 16) + 1) /**< PRS USART 1 TX complete */
-#define PRS_USART1_RXDATAV ((17 << 16) + 2) /**< PRS USART 1 RX Data Valid */
-#define PRS_TIMER0_UF ((28 << 16) + 0) /**< PRS Timer 0 Underflow */
-#define PRS_TIMER0_OF ((28 << 16) + 1) /**< PRS Timer 0 Overflow */
-#define PRS_TIMER0_CC0 ((28 << 16) + 2) /**< PRS Timer 0 Compare/Capture 0 */
-#define PRS_TIMER0_CC1 ((28 << 16) + 3) /**< PRS Timer 0 Compare/Capture 1 */
-#define PRS_TIMER0_CC2 ((28 << 16) + 4) /**< PRS Timer 0 Compare/Capture 2 */
-#define PRS_TIMER1_UF ((29 << 16) + 0) /**< PRS Timer 1 Underflow */
-#define PRS_TIMER1_OF ((29 << 16) + 1) /**< PRS Timer 1 Overflow */
-#define PRS_TIMER1_CC0 ((29 << 16) + 2) /**< PRS Timer 1 Compare/Capture 0 */
-#define PRS_TIMER1_CC1 ((29 << 16) + 3) /**< PRS Timer 1 Compare/Capture 1 */
-#define PRS_TIMER1_CC2 ((29 << 16) + 4) /**< PRS Timer 1 Compare/Capture 2 */
-#define PRS_RTC_OF ((40 << 16) + 0) /**< PRS RTC Overflow */
-#define PRS_RTC_COMP0 ((40 << 16) + 1) /**< PRS RTC Compare 0 */
-#define PRS_RTC_COMP1 ((40 << 16) + 2) /**< PRS RTC Compare 1 */
-#define PRS_GPIO_PIN0 ((48 << 16) + 0) /**< PRS GPIO pin 0 */
-#define PRS_GPIO_PIN1 ((48 << 16) + 1) /**< PRS GPIO pin 1 */
-#define PRS_GPIO_PIN2 ((48 << 16) + 2) /**< PRS GPIO pin 2 */
-#define PRS_GPIO_PIN3 ((48 << 16) + 3) /**< PRS GPIO pin 3 */
-#define PRS_GPIO_PIN4 ((48 << 16) + 4) /**< PRS GPIO pin 4 */
-#define PRS_GPIO_PIN5 ((48 << 16) + 5) /**< PRS GPIO pin 5 */
-#define PRS_GPIO_PIN6 ((48 << 16) + 6) /**< PRS GPIO pin 6 */
-#define PRS_GPIO_PIN7 ((48 << 16) + 7) /**< PRS GPIO pin 7 */
-#define PRS_GPIO_PIN8 ((49 << 16) + 0) /**< PRS GPIO pin 8 */
-#define PRS_GPIO_PIN9 ((49 << 16) + 1) /**< PRS GPIO pin 9 */
-#define PRS_GPIO_PIN10 ((49 << 16) + 2) /**< PRS GPIO pin 10 */
-#define PRS_GPIO_PIN11 ((49 << 16) + 3) /**< PRS GPIO pin 11 */
-#define PRS_GPIO_PIN12 ((49 << 16) + 4) /**< PRS GPIO pin 12 */
-#define PRS_GPIO_PIN13 ((49 << 16) + 5) /**< PRS GPIO pin 13 */
-#define PRS_GPIO_PIN14 ((49 << 16) + 6) /**< PRS GPIO pin 14 */
-#define PRS_GPIO_PIN15 ((49 << 16) + 7) /**< PRS GPIO pin 15 */
-#define PRS_PCNT0_TCC ((54 << 16) + 0) /**< PRS Triggered compare match */
-
-/** @} End of group EFM32ZG108F8_PRS */
-
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_DMA_BitFields EFM32ZG108F8_DMA Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for DMA STATUS */
-#define _DMA_STATUS_RESETVALUE 0x10030000UL /**< Default value for DMA_STATUS */
-#define _DMA_STATUS_MASK 0x001F00F1UL /**< Mask for DMA_STATUS */
-#define DMA_STATUS_EN (0x1UL << 0) /**< DMA Enable Status */
-#define _DMA_STATUS_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_STATUS_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_STATUS_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_EN_DEFAULT (_DMA_STATUS_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_SHIFT 4 /**< Shift value for DMA_STATE */
-#define _DMA_STATUS_STATE_MASK 0xF0UL /**< Bit mask for DMA_STATE */
-#define _DMA_STATUS_STATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_IDLE 0x00000000UL /**< Mode IDLE for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDCHCTRLDATA 0x00000001UL /**< Mode RDCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCENDPTR 0x00000002UL /**< Mode RDSRCENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDDSTENDPTR 0x00000003UL /**< Mode RDDSTENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCDATA 0x00000004UL /**< Mode RDSRCDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRDSTDATA 0x00000005UL /**< Mode WRDSTDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WAITREQCLR 0x00000006UL /**< Mode WAITREQCLR for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRCHCTRLDATA 0x00000007UL /**< Mode WRCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_STALLED 0x00000008UL /**< Mode STALLED for DMA_STATUS */
-#define _DMA_STATUS_STATE_DONE 0x00000009UL /**< Mode DONE for DMA_STATUS */
-#define _DMA_STATUS_STATE_PERSCATTRANS 0x0000000AUL /**< Mode PERSCATTRANS for DMA_STATUS */
-#define DMA_STATUS_STATE_DEFAULT (_DMA_STATUS_STATE_DEFAULT << 4) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_STATE_IDLE (_DMA_STATUS_STATE_IDLE << 4) /**< Shifted mode IDLE for DMA_STATUS */
-#define DMA_STATUS_STATE_RDCHCTRLDATA (_DMA_STATUS_STATE_RDCHCTRLDATA << 4) /**< Shifted mode RDCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCENDPTR (_DMA_STATUS_STATE_RDSRCENDPTR << 4) /**< Shifted mode RDSRCENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDDSTENDPTR (_DMA_STATUS_STATE_RDDSTENDPTR << 4) /**< Shifted mode RDDSTENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCDATA (_DMA_STATUS_STATE_RDSRCDATA << 4) /**< Shifted mode RDSRCDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WRDSTDATA (_DMA_STATUS_STATE_WRDSTDATA << 4) /**< Shifted mode WRDSTDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WAITREQCLR (_DMA_STATUS_STATE_WAITREQCLR << 4) /**< Shifted mode WAITREQCLR for DMA_STATUS */
-#define DMA_STATUS_STATE_WRCHCTRLDATA (_DMA_STATUS_STATE_WRCHCTRLDATA << 4) /**< Shifted mode WRCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_STALLED (_DMA_STATUS_STATE_STALLED << 4) /**< Shifted mode STALLED for DMA_STATUS */
-#define DMA_STATUS_STATE_DONE (_DMA_STATUS_STATE_DONE << 4) /**< Shifted mode DONE for DMA_STATUS */
-#define DMA_STATUS_STATE_PERSCATTRANS (_DMA_STATUS_STATE_PERSCATTRANS << 4) /**< Shifted mode PERSCATTRANS for DMA_STATUS */
-#define _DMA_STATUS_CHNUM_SHIFT 16 /**< Shift value for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_MASK 0x1F0000UL /**< Bit mask for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_DEFAULT 0x00000003UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_CHNUM_DEFAULT (_DMA_STATUS_CHNUM_DEFAULT << 16) /**< Shifted mode DEFAULT for DMA_STATUS */
-
-/* Bit fields for DMA CONFIG */
-#define _DMA_CONFIG_RESETVALUE 0x00000000UL /**< Default value for DMA_CONFIG */
-#define _DMA_CONFIG_MASK 0x00000021UL /**< Mask for DMA_CONFIG */
-#define DMA_CONFIG_EN (0x1UL << 0) /**< Enable DMA */
-#define _DMA_CONFIG_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_CONFIG_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_CONFIG_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_EN_DEFAULT (_DMA_CONFIG_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT (0x1UL << 5) /**< Channel Protection Control */
-#define _DMA_CONFIG_CHPROT_SHIFT 5 /**< Shift value for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_MASK 0x20UL /**< Bit mask for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT_DEFAULT (_DMA_CONFIG_CHPROT_DEFAULT << 5) /**< Shifted mode DEFAULT for DMA_CONFIG */
-
-/* Bit fields for DMA CTRLBASE */
-#define _DMA_CTRLBASE_RESETVALUE 0x00000000UL /**< Default value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_SHIFT 0 /**< Shift value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CTRLBASE */
-#define DMA_CTRLBASE_CTRLBASE_DEFAULT (_DMA_CTRLBASE_CTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CTRLBASE */
-
-/* Bit fields for DMA ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_RESETVALUE 0x00000040UL /**< Default value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_SHIFT 0 /**< Shift value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT 0x00000040UL /**< Mode DEFAULT for DMA_ALTCTRLBASE */
-#define DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT (_DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ALTCTRLBASE */
-
-/* Bit fields for DMA CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_RESETVALUE 0x0000000FUL /**< Default value for DMA_CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS (0x1UL << 0) /**< Channel 0 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_SHIFT 0 /**< Shift value for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS (0x1UL << 1) /**< Channel 1 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_SHIFT 1 /**< Shift value for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS (0x1UL << 2) /**< Channel 2 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_SHIFT 2 /**< Shift value for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS (0x1UL << 3) /**< Channel 3 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_SHIFT 3 /**< Shift value for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-
-/* Bit fields for DMA CHSWREQ */
-#define _DMA_CHSWREQ_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSWREQ */
-#define _DMA_CHSWREQ_MASK 0x0000000FUL /**< Mask for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ (0x1UL << 0) /**< Channel 0 Software Request */
-#define _DMA_CHSWREQ_CH0SWREQ_SHIFT 0 /**< Shift value for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_MASK 0x1UL /**< Bit mask for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ_DEFAULT (_DMA_CHSWREQ_CH0SWREQ_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ (0x1UL << 1) /**< Channel 1 Software Request */
-#define _DMA_CHSWREQ_CH1SWREQ_SHIFT 1 /**< Shift value for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_MASK 0x2UL /**< Bit mask for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ_DEFAULT (_DMA_CHSWREQ_CH1SWREQ_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ (0x1UL << 2) /**< Channel 2 Software Request */
-#define _DMA_CHSWREQ_CH2SWREQ_SHIFT 2 /**< Shift value for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_MASK 0x4UL /**< Bit mask for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ_DEFAULT (_DMA_CHSWREQ_CH2SWREQ_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ (0x1UL << 3) /**< Channel 3 Software Request */
-#define _DMA_CHSWREQ_CH3SWREQ_SHIFT 3 /**< Shift value for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_MASK 0x8UL /**< Bit mask for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ_DEFAULT (_DMA_CHSWREQ_CH3SWREQ_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-
-/* Bit fields for DMA CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS (0x1UL << 0) /**< Channel 0 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST 0x00000000UL /**< Mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY 0x00000001UL /**< Mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST (_DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST << 0) /**< Shifted mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY (_DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY << 0) /**< Shifted mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS (0x1UL << 1) /**< Channel 1 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS (0x1UL << 2) /**< Channel 2 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS (0x1UL << 3) /**< Channel 3 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-
-/* Bit fields for DMA CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC (0x1UL << 0) /**< Channel 0 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC (0x1UL << 1) /**< Channel 1 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC (0x1UL << 2) /**< Channel 2 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC (0x1UL << 3) /**< Channel 3 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-
-/* Bit fields for DMA CHREQMASKS */
-#define _DMA_CHREQMASKS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKS */
-#define _DMA_CHREQMASKS_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS (0x1UL << 0) /**< Channel 0 Request Mask Set */
-#define _DMA_CHREQMASKS_CH0REQMASKS_SHIFT 0 /**< Shift value for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH0REQMASKS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS (0x1UL << 1) /**< Channel 1 Request Mask Set */
-#define _DMA_CHREQMASKS_CH1REQMASKS_SHIFT 1 /**< Shift value for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH1REQMASKS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS (0x1UL << 2) /**< Channel 2 Request Mask Set */
-#define _DMA_CHREQMASKS_CH2REQMASKS_SHIFT 2 /**< Shift value for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH2REQMASKS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS (0x1UL << 3) /**< Channel 3 Request Mask Set */
-#define _DMA_CHREQMASKS_CH3REQMASKS_SHIFT 3 /**< Shift value for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH3REQMASKS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-
-/* Bit fields for DMA CHREQMASKC */
-#define _DMA_CHREQMASKC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKC */
-#define _DMA_CHREQMASKC_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC (0x1UL << 0) /**< Channel 0 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH0REQMASKC_SHIFT 0 /**< Shift value for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH0REQMASKC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC (0x1UL << 1) /**< Channel 1 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH1REQMASKC_SHIFT 1 /**< Shift value for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH1REQMASKC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC (0x1UL << 2) /**< Channel 2 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH2REQMASKC_SHIFT 2 /**< Shift value for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH2REQMASKC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC (0x1UL << 3) /**< Channel 3 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH3REQMASKC_SHIFT 3 /**< Shift value for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH3REQMASKC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-
-/* Bit fields for DMA CHENS */
-#define _DMA_CHENS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENS */
-#define _DMA_CHENS_MASK 0x0000000FUL /**< Mask for DMA_CHENS */
-#define DMA_CHENS_CH0ENS (0x1UL << 0) /**< Channel 0 Enable Set */
-#define _DMA_CHENS_CH0ENS_SHIFT 0 /**< Shift value for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_MASK 0x1UL /**< Bit mask for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH0ENS_DEFAULT (_DMA_CHENS_CH0ENS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS (0x1UL << 1) /**< Channel 1 Enable Set */
-#define _DMA_CHENS_CH1ENS_SHIFT 1 /**< Shift value for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_MASK 0x2UL /**< Bit mask for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS_DEFAULT (_DMA_CHENS_CH1ENS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS (0x1UL << 2) /**< Channel 2 Enable Set */
-#define _DMA_CHENS_CH2ENS_SHIFT 2 /**< Shift value for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_MASK 0x4UL /**< Bit mask for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS_DEFAULT (_DMA_CHENS_CH2ENS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS (0x1UL << 3) /**< Channel 3 Enable Set */
-#define _DMA_CHENS_CH3ENS_SHIFT 3 /**< Shift value for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_MASK 0x8UL /**< Bit mask for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS_DEFAULT (_DMA_CHENS_CH3ENS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENS */
-
-/* Bit fields for DMA CHENC */
-#define _DMA_CHENC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENC */
-#define _DMA_CHENC_MASK 0x0000000FUL /**< Mask for DMA_CHENC */
-#define DMA_CHENC_CH0ENC (0x1UL << 0) /**< Channel 0 Enable Clear */
-#define _DMA_CHENC_CH0ENC_SHIFT 0 /**< Shift value for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_MASK 0x1UL /**< Bit mask for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH0ENC_DEFAULT (_DMA_CHENC_CH0ENC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC (0x1UL << 1) /**< Channel 1 Enable Clear */
-#define _DMA_CHENC_CH1ENC_SHIFT 1 /**< Shift value for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_MASK 0x2UL /**< Bit mask for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC_DEFAULT (_DMA_CHENC_CH1ENC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC (0x1UL << 2) /**< Channel 2 Enable Clear */
-#define _DMA_CHENC_CH2ENC_SHIFT 2 /**< Shift value for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_MASK 0x4UL /**< Bit mask for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC_DEFAULT (_DMA_CHENC_CH2ENC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC (0x1UL << 3) /**< Channel 3 Enable Clear */
-#define _DMA_CHENC_CH3ENC_SHIFT 3 /**< Shift value for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_MASK 0x8UL /**< Bit mask for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC_DEFAULT (_DMA_CHENC_CH3ENC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENC */
-
-/* Bit fields for DMA CHALTS */
-#define _DMA_CHALTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTS */
-#define _DMA_CHALTS_MASK 0x0000000FUL /**< Mask for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS (0x1UL << 0) /**< Channel 0 Alternate Structure Set */
-#define _DMA_CHALTS_CH0ALTS_SHIFT 0 /**< Shift value for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_MASK 0x1UL /**< Bit mask for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS_DEFAULT (_DMA_CHALTS_CH0ALTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS (0x1UL << 1) /**< Channel 1 Alternate Structure Set */
-#define _DMA_CHALTS_CH1ALTS_SHIFT 1 /**< Shift value for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_MASK 0x2UL /**< Bit mask for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS_DEFAULT (_DMA_CHALTS_CH1ALTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS (0x1UL << 2) /**< Channel 2 Alternate Structure Set */
-#define _DMA_CHALTS_CH2ALTS_SHIFT 2 /**< Shift value for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_MASK 0x4UL /**< Bit mask for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS_DEFAULT (_DMA_CHALTS_CH2ALTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS (0x1UL << 3) /**< Channel 3 Alternate Structure Set */
-#define _DMA_CHALTS_CH3ALTS_SHIFT 3 /**< Shift value for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_MASK 0x8UL /**< Bit mask for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS_DEFAULT (_DMA_CHALTS_CH3ALTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTS */
-
-/* Bit fields for DMA CHALTC */
-#define _DMA_CHALTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTC */
-#define _DMA_CHALTC_MASK 0x0000000FUL /**< Mask for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC (0x1UL << 0) /**< Channel 0 Alternate Clear */
-#define _DMA_CHALTC_CH0ALTC_SHIFT 0 /**< Shift value for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_MASK 0x1UL /**< Bit mask for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC_DEFAULT (_DMA_CHALTC_CH0ALTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC (0x1UL << 1) /**< Channel 1 Alternate Clear */
-#define _DMA_CHALTC_CH1ALTC_SHIFT 1 /**< Shift value for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_MASK 0x2UL /**< Bit mask for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC_DEFAULT (_DMA_CHALTC_CH1ALTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC (0x1UL << 2) /**< Channel 2 Alternate Clear */
-#define _DMA_CHALTC_CH2ALTC_SHIFT 2 /**< Shift value for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_MASK 0x4UL /**< Bit mask for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC_DEFAULT (_DMA_CHALTC_CH2ALTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC (0x1UL << 3) /**< Channel 3 Alternate Clear */
-#define _DMA_CHALTC_CH3ALTC_SHIFT 3 /**< Shift value for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_MASK 0x8UL /**< Bit mask for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC_DEFAULT (_DMA_CHALTC_CH3ALTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTC */
-
-/* Bit fields for DMA CHPRIS */
-#define _DMA_CHPRIS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIS */
-#define _DMA_CHPRIS_MASK 0x0000000FUL /**< Mask for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS (0x1UL << 0) /**< Channel 0 High Priority Set */
-#define _DMA_CHPRIS_CH0PRIS_SHIFT 0 /**< Shift value for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_MASK 0x1UL /**< Bit mask for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS_DEFAULT (_DMA_CHPRIS_CH0PRIS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS (0x1UL << 1) /**< Channel 1 High Priority Set */
-#define _DMA_CHPRIS_CH1PRIS_SHIFT 1 /**< Shift value for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_MASK 0x2UL /**< Bit mask for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS_DEFAULT (_DMA_CHPRIS_CH1PRIS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS (0x1UL << 2) /**< Channel 2 High Priority Set */
-#define _DMA_CHPRIS_CH2PRIS_SHIFT 2 /**< Shift value for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_MASK 0x4UL /**< Bit mask for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS_DEFAULT (_DMA_CHPRIS_CH2PRIS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS (0x1UL << 3) /**< Channel 3 High Priority Set */
-#define _DMA_CHPRIS_CH3PRIS_SHIFT 3 /**< Shift value for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_MASK 0x8UL /**< Bit mask for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS_DEFAULT (_DMA_CHPRIS_CH3PRIS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-
-/* Bit fields for DMA CHPRIC */
-#define _DMA_CHPRIC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIC */
-#define _DMA_CHPRIC_MASK 0x0000000FUL /**< Mask for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC (0x1UL << 0) /**< Channel 0 High Priority Clear */
-#define _DMA_CHPRIC_CH0PRIC_SHIFT 0 /**< Shift value for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_MASK 0x1UL /**< Bit mask for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC_DEFAULT (_DMA_CHPRIC_CH0PRIC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC (0x1UL << 1) /**< Channel 1 High Priority Clear */
-#define _DMA_CHPRIC_CH1PRIC_SHIFT 1 /**< Shift value for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_MASK 0x2UL /**< Bit mask for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC_DEFAULT (_DMA_CHPRIC_CH1PRIC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC (0x1UL << 2) /**< Channel 2 High Priority Clear */
-#define _DMA_CHPRIC_CH2PRIC_SHIFT 2 /**< Shift value for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_MASK 0x4UL /**< Bit mask for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC_DEFAULT (_DMA_CHPRIC_CH2PRIC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC (0x1UL << 3) /**< Channel 3 High Priority Clear */
-#define _DMA_CHPRIC_CH3PRIC_SHIFT 3 /**< Shift value for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_MASK 0x8UL /**< Bit mask for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC_DEFAULT (_DMA_CHPRIC_CH3PRIC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-
-/* Bit fields for DMA ERRORC */
-#define _DMA_ERRORC_RESETVALUE 0x00000000UL /**< Default value for DMA_ERRORC */
-#define _DMA_ERRORC_MASK 0x00000001UL /**< Mask for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC (0x1UL << 0) /**< Bus Error Clear */
-#define _DMA_ERRORC_ERRORC_SHIFT 0 /**< Shift value for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_MASK 0x1UL /**< Bit mask for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC_DEFAULT (_DMA_ERRORC_ERRORC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ERRORC */
-
-/* Bit fields for DMA CHREQSTATUS */
-#define _DMA_CHREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQSTATUS */
-#define _DMA_CHREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS (0x1UL << 0) /**< Channel 0 Request Status */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS (0x1UL << 1) /**< Channel 1 Request Status */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS (0x1UL << 2) /**< Channel 2 Request Status */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS (0x1UL << 3) /**< Channel 3 Request Status */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-
-/* Bit fields for DMA CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS (0x1UL << 0) /**< Channel 0 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS (0x1UL << 1) /**< Channel 1 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS (0x1UL << 2) /**< Channel 2 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS (0x1UL << 3) /**< Channel 3 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-
-/* Bit fields for DMA IF */
-#define _DMA_IF_RESETVALUE 0x00000000UL /**< Default value for DMA_IF */
-#define _DMA_IF_MASK 0x8000000FUL /**< Mask for DMA_IF */
-#define DMA_IF_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag */
-#define _DMA_IF_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH0DONE_DEFAULT (_DMA_IF_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag */
-#define _DMA_IF_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE_DEFAULT (_DMA_IF_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag */
-#define _DMA_IF_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE_DEFAULT (_DMA_IF_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag */
-#define _DMA_IF_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE_DEFAULT (_DMA_IF_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag */
-#define _DMA_IF_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IF_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IF_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR_DEFAULT (_DMA_IF_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IF */
-
-/* Bit fields for DMA IFS */
-#define _DMA_IFS_RESETVALUE 0x00000000UL /**< Default value for DMA_IFS */
-#define _DMA_IFS_MASK 0x8000000FUL /**< Mask for DMA_IFS */
-#define DMA_IFS_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH0DONE_DEFAULT (_DMA_IFS_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE_DEFAULT (_DMA_IFS_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE_DEFAULT (_DMA_IFS_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE_DEFAULT (_DMA_IFS_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Set */
-#define _DMA_IFS_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFS_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFS_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR_DEFAULT (_DMA_IFS_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFS */
-
-/* Bit fields for DMA IFC */
-#define _DMA_IFC_RESETVALUE 0x00000000UL /**< Default value for DMA_IFC */
-#define _DMA_IFC_MASK 0x8000000FUL /**< Mask for DMA_IFC */
-#define DMA_IFC_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH0DONE_DEFAULT (_DMA_IFC_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE_DEFAULT (_DMA_IFC_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE_DEFAULT (_DMA_IFC_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE_DEFAULT (_DMA_IFC_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Clear */
-#define _DMA_IFC_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFC_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFC_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR_DEFAULT (_DMA_IFC_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFC */
-
-/* Bit fields for DMA IEN */
-#define _DMA_IEN_RESETVALUE 0x00000000UL /**< Default value for DMA_IEN */
-#define _DMA_IEN_MASK 0x8000000FUL /**< Mask for DMA_IEN */
-#define DMA_IEN_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Enable */
-#define _DMA_IEN_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH0DONE_DEFAULT (_DMA_IEN_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Enable */
-#define _DMA_IEN_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE_DEFAULT (_DMA_IEN_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Enable */
-#define _DMA_IEN_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE_DEFAULT (_DMA_IEN_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Enable */
-#define _DMA_IEN_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE_DEFAULT (_DMA_IEN_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Enable */
-#define _DMA_IEN_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IEN_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IEN_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR_DEFAULT (_DMA_IEN_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IEN */
-
-/* Bit fields for DMA CH_CTRL */
-#define _DMA_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_MASK 0x003F000FUL /**< Mask for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_MASK 0xFUL /**< Bit mask for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000000UL /**< Mode USART1RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV 0x00000000UL /**< Mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0RXDATAV 0x00000000UL /**< Mode I2C0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0UFOF 0x00000000UL /**< Mode TIMER0UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1UFOF 0x00000000UL /**< Mode TIMER1UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_MSCWDATA 0x00000000UL /**< Mode MSCWDATA for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBL 0x00000001UL /**< Mode USART1TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXBL 0x00000001UL /**< Mode LEUART0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0TXBL 0x00000001UL /**< Mode I2C0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC0 0x00000001UL /**< Mode TIMER0CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC0 0x00000001UL /**< Mode TIMER1CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXEMPTY 0x00000002UL /**< Mode USART1TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY 0x00000002UL /**< Mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC1 0x00000002UL /**< Mode TIMER0CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC1 0x00000002UL /**< Mode TIMER1CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT 0x00000003UL /**< Mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC2 0x00000003UL /**< Mode TIMER0CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC2 0x00000003UL /**< Mode TIMER1CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT 0x00000004UL /**< Mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAV (_DMA_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV (_DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV << 0) /**< Shifted mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0RXDATAV (_DMA_CH_CTRL_SIGSEL_I2C0RXDATAV << 0) /**< Shifted mode I2C0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0UFOF (_DMA_CH_CTRL_SIGSEL_TIMER0UFOF << 0) /**< Shifted mode TIMER0UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1UFOF (_DMA_CH_CTRL_SIGSEL_TIMER1UFOF << 0) /**< Shifted mode TIMER1UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_MSCWDATA (_DMA_CH_CTRL_SIGSEL_MSCWDATA << 0) /**< Shifted mode MSCWDATA for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBL (_DMA_CH_CTRL_SIGSEL_USART1TXBL << 0) /**< Shifted mode USART1TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXBL (_DMA_CH_CTRL_SIGSEL_LEUART0TXBL << 0) /**< Shifted mode LEUART0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0TXBL (_DMA_CH_CTRL_SIGSEL_I2C0TXBL << 0) /**< Shifted mode I2C0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC0 (_DMA_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC0 (_DMA_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXEMPTY (_DMA_CH_CTRL_SIGSEL_USART1TXEMPTY << 0) /**< Shifted mode USART1TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY (_DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY << 0) /**< Shifted mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC1 (_DMA_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC1 (_DMA_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT (_DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT << 0) /**< Shifted mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC2 (_DMA_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC2 (_DMA_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT (_DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT << 0) /**< Shifted mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_USART1 0x0000000DUL /**< Mode USART1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_LEUART0 0x00000010UL /**< Mode LEUART0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_I2C0 0x00000014UL /**< Mode I2C0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER0 0x00000018UL /**< Mode TIMER0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER1 0x00000019UL /**< Mode TIMER1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_MSC 0x00000030UL /**< Mode MSC for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_NONE (_DMA_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_USART1 (_DMA_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_LEUART0 (_DMA_CH_CTRL_SOURCESEL_LEUART0 << 16) /**< Shifted mode LEUART0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_I2C0 (_DMA_CH_CTRL_SOURCESEL_I2C0 << 16) /**< Shifted mode I2C0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER0 (_DMA_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER1 (_DMA_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_MSC (_DMA_CH_CTRL_SOURCESEL_MSC << 16) /**< Shifted mode MSC for DMA_CH_CTRL */
-
-/** @} End of group EFM32ZG108F8_DMA */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_CMU_BitFields EFM32ZG108F8_CMU Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for CMU CTRL */
-#define _CMU_CTRL_RESETVALUE 0x000C262CUL /**< Default value for CMU_CTRL */
-#define _CMU_CTRL_MASK 0x07FE3EEFUL /**< Mask for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_SHIFT 0 /**< Shift value for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_MASK 0x3UL /**< Bit mask for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DEFAULT (_CMU_CTRL_HFXOMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_XTAL (_CMU_CTRL_HFXOMODE_XTAL << 0) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_BUFEXTCLK (_CMU_CTRL_HFXOMODE_BUFEXTCLK << 0) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DIGEXTCLK (_CMU_CTRL_HFXOMODE_DIGEXTCLK << 0) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_SHIFT 2 /**< Shift value for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_MASK 0xCUL /**< Bit mask for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_50PCENT 0x00000000UL /**< Mode 50PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_70PCENT 0x00000001UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_80PCENT 0x00000002UL /**< Mode 80PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_100PCENT 0x00000003UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_50PCENT (_CMU_CTRL_HFXOBOOST_50PCENT << 2) /**< Shifted mode 50PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_70PCENT (_CMU_CTRL_HFXOBOOST_70PCENT << 2) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_80PCENT (_CMU_CTRL_HFXOBOOST_80PCENT << 2) /**< Shifted mode 80PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_DEFAULT (_CMU_CTRL_HFXOBOOST_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_100PCENT (_CMU_CTRL_HFXOBOOST_100PCENT << 2) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBUFCUR_SHIFT 5 /**< Shift value for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_MASK 0x60UL /**< Bit mask for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBUFCUR_DEFAULT (_CMU_CTRL_HFXOBUFCUR_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN (0x1UL << 7) /**< HFXO Glitch Detector Enable */
-#define _CMU_CTRL_HFXOGLITCHDETEN_SHIFT 7 /**< Shift value for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_MASK 0x80UL /**< Bit mask for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN_DEFAULT (_CMU_CTRL_HFXOGLITCHDETEN_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_SHIFT 9 /**< Shift value for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_MASK 0x600UL /**< Bit mask for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_256CYCLES 0x00000001UL /**< Mode 256CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_1KCYCLES 0x00000002UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_16KCYCLES 0x00000003UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_8CYCLES (_CMU_CTRL_HFXOTIMEOUT_8CYCLES << 9) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_256CYCLES (_CMU_CTRL_HFXOTIMEOUT_256CYCLES << 9) /**< Shifted mode 256CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_1KCYCLES (_CMU_CTRL_HFXOTIMEOUT_1KCYCLES << 9) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_DEFAULT (_CMU_CTRL_HFXOTIMEOUT_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_16KCYCLES (_CMU_CTRL_HFXOTIMEOUT_16KCYCLES << 9) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_SHIFT 11 /**< Shift value for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_MASK 0x1800UL /**< Bit mask for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DEFAULT (_CMU_CTRL_LFXOMODE_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_XTAL (_CMU_CTRL_LFXOMODE_XTAL << 11) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_BUFEXTCLK (_CMU_CTRL_LFXOMODE_BUFEXTCLK << 11) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DIGEXTCLK (_CMU_CTRL_LFXOMODE_DIGEXTCLK << 11) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST (0x1UL << 13) /**< LFXO Start-up Boost Current */
-#define _CMU_CTRL_LFXOBOOST_SHIFT 13 /**< Shift value for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_MASK 0x2000UL /**< Bit mask for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_70PCENT 0x00000000UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_100PCENT 0x00000001UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_70PCENT (_CMU_CTRL_LFXOBOOST_70PCENT << 13) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_DEFAULT (_CMU_CTRL_LFXOBOOST_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_100PCENT (_CMU_CTRL_LFXOBOOST_100PCENT << 13) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR (0x1UL << 17) /**< LFXO Boost Buffer Current */
-#define _CMU_CTRL_LFXOBUFCUR_SHIFT 17 /**< Shift value for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_MASK 0x20000UL /**< Bit mask for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR_DEFAULT (_CMU_CTRL_LFXOBUFCUR_DEFAULT << 17) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_SHIFT 18 /**< Shift value for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_MASK 0xC0000UL /**< Bit mask for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_1KCYCLES 0x00000001UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_16KCYCLES 0x00000002UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_32KCYCLES 0x00000003UL /**< Mode 32KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_8CYCLES (_CMU_CTRL_LFXOTIMEOUT_8CYCLES << 18) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_1KCYCLES (_CMU_CTRL_LFXOTIMEOUT_1KCYCLES << 18) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_16KCYCLES (_CMU_CTRL_LFXOTIMEOUT_16KCYCLES << 18) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_DEFAULT (_CMU_CTRL_LFXOTIMEOUT_DEFAULT << 18) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_32KCYCLES (_CMU_CTRL_LFXOTIMEOUT_32KCYCLES << 18) /**< Shifted mode 32KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_SHIFT 20 /**< Shift value for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_MASK 0x700000UL /**< Bit mask for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFRCO 0x00000000UL /**< Mode HFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFXO 0x00000001UL /**< Mode HFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK2 0x00000002UL /**< Mode HFCLK2 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK4 0x00000003UL /**< Mode HFCLK4 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK8 0x00000004UL /**< Mode HFCLK8 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK16 0x00000005UL /**< Mode HFCLK16 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_ULFRCO 0x00000006UL /**< Mode ULFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_AUXHFRCO 0x00000007UL /**< Mode AUXHFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_DEFAULT (_CMU_CTRL_CLKOUTSEL0_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFRCO (_CMU_CTRL_CLKOUTSEL0_HFRCO << 20) /**< Shifted mode HFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFXO (_CMU_CTRL_CLKOUTSEL0_HFXO << 20) /**< Shifted mode HFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK2 (_CMU_CTRL_CLKOUTSEL0_HFCLK2 << 20) /**< Shifted mode HFCLK2 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK4 (_CMU_CTRL_CLKOUTSEL0_HFCLK4 << 20) /**< Shifted mode HFCLK4 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK8 (_CMU_CTRL_CLKOUTSEL0_HFCLK8 << 20) /**< Shifted mode HFCLK8 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK16 (_CMU_CTRL_CLKOUTSEL0_HFCLK16 << 20) /**< Shifted mode HFCLK16 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_ULFRCO (_CMU_CTRL_CLKOUTSEL0_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_AUXHFRCO (_CMU_CTRL_CLKOUTSEL0_AUXHFRCO << 20) /**< Shifted mode AUXHFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_SHIFT 23 /**< Shift value for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_MASK 0x7800000UL /**< Bit mask for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCO 0x00000000UL /**< Mode LFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXO 0x00000001UL /**< Mode LFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFCLK 0x00000002UL /**< Mode HFCLK for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXOQ 0x00000003UL /**< Mode LFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFXOQ 0x00000004UL /**< Mode HFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCOQ 0x00000005UL /**< Mode LFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFRCOQ 0x00000006UL /**< Mode HFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ 0x00000007UL /**< Mode AUXHFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_DEFAULT (_CMU_CTRL_CLKOUTSEL1_DEFAULT << 23) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCO (_CMU_CTRL_CLKOUTSEL1_LFRCO << 23) /**< Shifted mode LFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXO (_CMU_CTRL_CLKOUTSEL1_LFXO << 23) /**< Shifted mode LFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFCLK (_CMU_CTRL_CLKOUTSEL1_HFCLK << 23) /**< Shifted mode HFCLK for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXOQ (_CMU_CTRL_CLKOUTSEL1_LFXOQ << 23) /**< Shifted mode LFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFXOQ (_CMU_CTRL_CLKOUTSEL1_HFXOQ << 23) /**< Shifted mode HFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCOQ (_CMU_CTRL_CLKOUTSEL1_LFRCOQ << 23) /**< Shifted mode LFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFRCOQ (_CMU_CTRL_CLKOUTSEL1_HFRCOQ << 23) /**< Shifted mode HFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ (_CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ << 23) /**< Shifted mode AUXHFRCOQ for CMU_CTRL */
-
-/* Bit fields for CMU HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_SHIFT 0 /**< Shift value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV (0x1UL << 8) /**< Additional Division Factor For HFCORECLKLE */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_SHIFT 8 /**< Shift value for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_MASK 0x100UL /**< Bit mask for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 0x00000000UL /**< Mode DIV2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 0x00000001UL /**< Mode DIV4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 << 8) /**< Shifted mode DIV2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 << 8) /**< Shifted mode DIV4 for CMU_HFCORECLKDIV */
-
-/* Bit fields for CMU HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_RESETVALUE 0x00000100UL /**< Default value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_SHIFT 0 /**< Shift value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN (0x1UL << 8) /**< HFPERCLK Enable */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_SHIFT 8 /**< Shift value for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_MASK 0x100UL /**< Bit mask for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-
-/* Bit fields for CMU HFRCOCTRL */
-#define _CMU_HFRCOCTRL_RESETVALUE 0x00000380UL /**< Default value for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_MASK 0x0001F7FFUL /**< Mask for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_TUNING_DEFAULT (_CMU_HFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_1MHZ 0x00000000UL /**< Mode 1MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_7MHZ 0x00000001UL /**< Mode 7MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_11MHZ 0x00000002UL /**< Mode 11MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_14MHZ 0x00000003UL /**< Mode 14MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_21MHZ 0x00000004UL /**< Mode 21MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_1MHZ (_CMU_HFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_7MHZ (_CMU_HFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_11MHZ (_CMU_HFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_DEFAULT (_CMU_HFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_14MHZ (_CMU_HFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_21MHZ (_CMU_HFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_SUDELAY_SHIFT 12 /**< Shift value for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_MASK 0x1F000UL /**< Bit mask for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_SUDELAY_DEFAULT (_CMU_HFRCOCTRL_SUDELAY_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-
-/* Bit fields for CMU LFRCOCTRL */
-#define _CMU_LFRCOCTRL_RESETVALUE 0x00000040UL /**< Default value for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_MASK 0x0000007FUL /**< Mask for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_MASK 0x7FUL /**< Bit mask for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_DEFAULT 0x00000040UL /**< Mode DEFAULT for CMU_LFRCOCTRL */
-#define CMU_LFRCOCTRL_TUNING_DEFAULT (_CMU_LFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFRCOCTRL */
-
-/* Bit fields for CMU AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_RESETVALUE 0x00000080UL /**< Default value for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_MASK 0x000007FFUL /**< Mask for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_TUNING_DEFAULT (_CMU_AUXHFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_14MHZ 0x00000000UL /**< Mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_11MHZ 0x00000001UL /**< Mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_7MHZ 0x00000002UL /**< Mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_1MHZ 0x00000003UL /**< Mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_21MHZ 0x00000007UL /**< Mode 21MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_DEFAULT (_CMU_AUXHFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_14MHZ (_CMU_AUXHFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_11MHZ (_CMU_AUXHFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_7MHZ (_CMU_AUXHFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_1MHZ (_CMU_AUXHFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_21MHZ (_CMU_AUXHFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_AUXHFRCOCTRL */
-
-/* Bit fields for CMU CALCTRL */
-#define _CMU_CALCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCTRL */
-#define _CMU_CALCTRL_MASK 0x0000007FUL /**< Mask for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_SHIFT 0 /**< Shift value for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_MASK 0x7UL /**< Bit mask for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFXO 0x00000000UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFXO 0x00000001UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFRCO 0x00000002UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_AUXHFRCO 0x00000004UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_DEFAULT (_CMU_CALCTRL_UPSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFXO (_CMU_CALCTRL_UPSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFXO (_CMU_CALCTRL_UPSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFRCO (_CMU_CALCTRL_UPSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFRCO (_CMU_CALCTRL_UPSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_AUXHFRCO (_CMU_CALCTRL_UPSEL_AUXHFRCO << 0) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_SHIFT 3 /**< Shift value for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_MASK 0x38UL /**< Bit mask for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFXO 0x00000001UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFXO 0x00000002UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFRCO 0x00000003UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFRCO 0x00000004UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_AUXHFRCO 0x00000005UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_DEFAULT (_CMU_CALCTRL_DOWNSEL_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFCLK (_CMU_CALCTRL_DOWNSEL_HFCLK << 3) /**< Shifted mode HFCLK for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFXO (_CMU_CALCTRL_DOWNSEL_HFXO << 3) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFXO (_CMU_CALCTRL_DOWNSEL_LFXO << 3) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFRCO (_CMU_CALCTRL_DOWNSEL_HFRCO << 3) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFRCO (_CMU_CALCTRL_DOWNSEL_LFRCO << 3) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_AUXHFRCO (_CMU_CALCTRL_DOWNSEL_AUXHFRCO << 3) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT (0x1UL << 6) /**< Continuous Calibration */
-#define _CMU_CALCTRL_CONT_SHIFT 6 /**< Shift value for CMU_CONT */
-#define _CMU_CALCTRL_CONT_MASK 0x40UL /**< Bit mask for CMU_CONT */
-#define _CMU_CALCTRL_CONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT_DEFAULT (_CMU_CALCTRL_CONT_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-
-/* Bit fields for CMU CALCNT */
-#define _CMU_CALCNT_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCNT */
-#define _CMU_CALCNT_MASK 0x000FFFFFUL /**< Mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_SHIFT 0 /**< Shift value for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_MASK 0xFFFFFUL /**< Bit mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCNT */
-#define CMU_CALCNT_CALCNT_DEFAULT (_CMU_CALCNT_CALCNT_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCNT */
-
-/* Bit fields for CMU OSCENCMD */
-#define _CMU_OSCENCMD_RESETVALUE 0x00000000UL /**< Default value for CMU_OSCENCMD */
-#define _CMU_OSCENCMD_MASK 0x000003FFUL /**< Mask for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN (0x1UL << 0) /**< HFRCO Enable */
-#define _CMU_OSCENCMD_HFRCOEN_SHIFT 0 /**< Shift value for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_MASK 0x1UL /**< Bit mask for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN_DEFAULT (_CMU_OSCENCMD_HFRCOEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS (0x1UL << 1) /**< HFRCO Disable */
-#define _CMU_OSCENCMD_HFRCODIS_SHIFT 1 /**< Shift value for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_MASK 0x2UL /**< Bit mask for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS_DEFAULT (_CMU_OSCENCMD_HFRCODIS_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN (0x1UL << 2) /**< HFXO Enable */
-#define _CMU_OSCENCMD_HFXOEN_SHIFT 2 /**< Shift value for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_MASK 0x4UL /**< Bit mask for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN_DEFAULT (_CMU_OSCENCMD_HFXOEN_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS (0x1UL << 3) /**< HFXO Disable */
-#define _CMU_OSCENCMD_HFXODIS_SHIFT 3 /**< Shift value for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_MASK 0x8UL /**< Bit mask for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS_DEFAULT (_CMU_OSCENCMD_HFXODIS_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN (0x1UL << 4) /**< AUXHFRCO Enable */
-#define _CMU_OSCENCMD_AUXHFRCOEN_SHIFT 4 /**< Shift value for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN_DEFAULT (_CMU_OSCENCMD_AUXHFRCOEN_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS (0x1UL << 5) /**< AUXHFRCO Disable */
-#define _CMU_OSCENCMD_AUXHFRCODIS_SHIFT 5 /**< Shift value for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS_DEFAULT (_CMU_OSCENCMD_AUXHFRCODIS_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN (0x1UL << 6) /**< LFRCO Enable */
-#define _CMU_OSCENCMD_LFRCOEN_SHIFT 6 /**< Shift value for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_MASK 0x40UL /**< Bit mask for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN_DEFAULT (_CMU_OSCENCMD_LFRCOEN_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS (0x1UL << 7) /**< LFRCO Disable */
-#define _CMU_OSCENCMD_LFRCODIS_SHIFT 7 /**< Shift value for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_MASK 0x80UL /**< Bit mask for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS_DEFAULT (_CMU_OSCENCMD_LFRCODIS_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN (0x1UL << 8) /**< LFXO Enable */
-#define _CMU_OSCENCMD_LFXOEN_SHIFT 8 /**< Shift value for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_MASK 0x100UL /**< Bit mask for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN_DEFAULT (_CMU_OSCENCMD_LFXOEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS (0x1UL << 9) /**< LFXO Disable */
-#define _CMU_OSCENCMD_LFXODIS_SHIFT 9 /**< Shift value for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_MASK 0x200UL /**< Bit mask for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS_DEFAULT (_CMU_OSCENCMD_LFXODIS_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-
-/* Bit fields for CMU CMD */
-#define _CMU_CMD_RESETVALUE 0x00000000UL /**< Default value for CMU_CMD */
-#define _CMU_CMD_MASK 0x0000001FUL /**< Mask for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_SHIFT 0 /**< Shift value for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_MASK 0x7UL /**< Bit mask for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFRCO 0x00000001UL /**< Mode HFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFXO 0x00000002UL /**< Mode HFXO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFXO 0x00000004UL /**< Mode LFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_DEFAULT (_CMU_CMD_HFCLKSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFRCO (_CMU_CMD_HFCLKSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFXO (_CMU_CMD_HFCLKSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFRCO (_CMU_CMD_HFCLKSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFXO (_CMU_CMD_HFCLKSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CMD */
-#define CMU_CMD_CALSTART (0x1UL << 3) /**< Calibration Start */
-#define _CMU_CMD_CALSTART_SHIFT 3 /**< Shift value for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_MASK 0x8UL /**< Bit mask for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTART_DEFAULT (_CMU_CMD_CALSTART_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP (0x1UL << 4) /**< Calibration Stop */
-#define _CMU_CMD_CALSTOP_SHIFT 4 /**< Shift value for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_MASK 0x10UL /**< Bit mask for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP_DEFAULT (_CMU_CMD_CALSTOP_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_CMD */
-
-/* Bit fields for CMU LFCLKSEL */
-#define _CMU_LFCLKSEL_RESETVALUE 0x00000005UL /**< Default value for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_MASK 0x0011000FUL /**< Mask for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_SHIFT 0 /**< Shift value for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_MASK 0x3UL /**< Bit mask for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DISABLED (_CMU_LFCLKSEL_LFA_DISABLED << 0) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DEFAULT (_CMU_LFCLKSEL_LFA_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFRCO (_CMU_LFCLKSEL_LFA_LFRCO << 0) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFXO (_CMU_LFCLKSEL_LFA_LFXO << 0) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 << 0) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_SHIFT 2 /**< Shift value for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_MASK 0xCUL /**< Bit mask for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DISABLED (_CMU_LFCLKSEL_LFB_DISABLED << 2) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DEFAULT (_CMU_LFCLKSEL_LFB_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFRCO (_CMU_LFCLKSEL_LFB_LFRCO << 2) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFXO (_CMU_LFCLKSEL_LFB_LFXO << 2) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 << 2) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE (0x1UL << 16) /**< Clock Select for LFA Extended */
-#define _CMU_LFCLKSEL_LFAE_SHIFT 16 /**< Shift value for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_MASK 0x10000UL /**< Bit mask for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DEFAULT (_CMU_LFCLKSEL_LFAE_DEFAULT << 16) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DISABLED (_CMU_LFCLKSEL_LFAE_DISABLED << 16) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_ULFRCO (_CMU_LFCLKSEL_LFAE_ULFRCO << 16) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE (0x1UL << 20) /**< Clock Select for LFB Extended */
-#define _CMU_LFCLKSEL_LFBE_SHIFT 20 /**< Shift value for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_MASK 0x100000UL /**< Bit mask for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DEFAULT (_CMU_LFCLKSEL_LFBE_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DISABLED (_CMU_LFCLKSEL_LFBE_DISABLED << 20) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_ULFRCO (_CMU_LFCLKSEL_LFBE_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-
-/* Bit fields for CMU STATUS */
-#define _CMU_STATUS_RESETVALUE 0x00000403UL /**< Default value for CMU_STATUS */
-#define _CMU_STATUS_MASK 0x00007FFFUL /**< Mask for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS (0x1UL << 0) /**< HFRCO Enable Status */
-#define _CMU_STATUS_HFRCOENS_SHIFT 0 /**< Shift value for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_MASK 0x1UL /**< Bit mask for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS_DEFAULT (_CMU_STATUS_HFRCOENS_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY (0x1UL << 1) /**< HFRCO Ready */
-#define _CMU_STATUS_HFRCORDY_SHIFT 1 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_MASK 0x2UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY_DEFAULT (_CMU_STATUS_HFRCORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS (0x1UL << 2) /**< HFXO Enable Status */
-#define _CMU_STATUS_HFXOENS_SHIFT 2 /**< Shift value for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_MASK 0x4UL /**< Bit mask for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS_DEFAULT (_CMU_STATUS_HFXOENS_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY (0x1UL << 3) /**< HFXO Ready */
-#define _CMU_STATUS_HFXORDY_SHIFT 3 /**< Shift value for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_MASK 0x8UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY_DEFAULT (_CMU_STATUS_HFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS (0x1UL << 4) /**< AUXHFRCO Enable Status */
-#define _CMU_STATUS_AUXHFRCOENS_SHIFT 4 /**< Shift value for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS_DEFAULT (_CMU_STATUS_AUXHFRCOENS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY (0x1UL << 5) /**< AUXHFRCO Ready */
-#define _CMU_STATUS_AUXHFRCORDY_SHIFT 5 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY_DEFAULT (_CMU_STATUS_AUXHFRCORDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS (0x1UL << 6) /**< LFRCO Enable Status */
-#define _CMU_STATUS_LFRCOENS_SHIFT 6 /**< Shift value for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_MASK 0x40UL /**< Bit mask for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS_DEFAULT (_CMU_STATUS_LFRCOENS_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY (0x1UL << 7) /**< LFRCO Ready */
-#define _CMU_STATUS_LFRCORDY_SHIFT 7 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_MASK 0x80UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY_DEFAULT (_CMU_STATUS_LFRCORDY_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS (0x1UL << 8) /**< LFXO Enable Status */
-#define _CMU_STATUS_LFXOENS_SHIFT 8 /**< Shift value for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_MASK 0x100UL /**< Bit mask for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS_DEFAULT (_CMU_STATUS_LFXOENS_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY (0x1UL << 9) /**< LFXO Ready */
-#define _CMU_STATUS_LFXORDY_SHIFT 9 /**< Shift value for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_MASK 0x200UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY_DEFAULT (_CMU_STATUS_LFXORDY_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL (0x1UL << 10) /**< HFRCO Selected */
-#define _CMU_STATUS_HFRCOSEL_SHIFT 10 /**< Shift value for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_MASK 0x400UL /**< Bit mask for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL_DEFAULT (_CMU_STATUS_HFRCOSEL_DEFAULT << 10) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL (0x1UL << 11) /**< HFXO Selected */
-#define _CMU_STATUS_HFXOSEL_SHIFT 11 /**< Shift value for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_MASK 0x800UL /**< Bit mask for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL_DEFAULT (_CMU_STATUS_HFXOSEL_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL (0x1UL << 12) /**< LFRCO Selected */
-#define _CMU_STATUS_LFRCOSEL_SHIFT 12 /**< Shift value for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_MASK 0x1000UL /**< Bit mask for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL_DEFAULT (_CMU_STATUS_LFRCOSEL_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL (0x1UL << 13) /**< LFXO Selected */
-#define _CMU_STATUS_LFXOSEL_SHIFT 13 /**< Shift value for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_MASK 0x2000UL /**< Bit mask for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL_DEFAULT (_CMU_STATUS_LFXOSEL_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY (0x1UL << 14) /**< Calibration Busy */
-#define _CMU_STATUS_CALBSY_SHIFT 14 /**< Shift value for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_MASK 0x4000UL /**< Bit mask for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY_DEFAULT (_CMU_STATUS_CALBSY_DEFAULT << 14) /**< Shifted mode DEFAULT for CMU_STATUS */
-
-/* Bit fields for CMU IF */
-#define _CMU_IF_RESETVALUE 0x00000001UL /**< Default value for CMU_IF */
-#define _CMU_IF_MASK 0x0000007FUL /**< Mask for CMU_IF */
-#define CMU_IF_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag */
-#define _CMU_IF_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFRCORDY_DEFAULT (_CMU_IF_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag */
-#define _CMU_IF_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY_DEFAULT (_CMU_IF_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag */
-#define _CMU_IF_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY_DEFAULT (_CMU_IF_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag */
-#define _CMU_IF_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY_DEFAULT (_CMU_IF_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag */
-#define _CMU_IF_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY_DEFAULT (_CMU_IF_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag */
-#define _CMU_IF_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IF_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IF_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY_DEFAULT (_CMU_IF_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag */
-#define _CMU_IF_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IF_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IF_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF_DEFAULT (_CMU_IF_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IF */
-
-/* Bit fields for CMU IFS */
-#define _CMU_IFS_RESETVALUE 0x00000000UL /**< Default value for CMU_IFS */
-#define _CMU_IFS_MASK 0x0000007FUL /**< Mask for CMU_IFS */
-#define CMU_IFS_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFRCORDY_DEFAULT (_CMU_IFS_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY_DEFAULT (_CMU_IFS_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY_DEFAULT (_CMU_IFS_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY_DEFAULT (_CMU_IFS_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY_DEFAULT (_CMU_IFS_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Set */
-#define _CMU_IFS_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY_DEFAULT (_CMU_IFS_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Set */
-#define _CMU_IFS_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFS_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFS_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF_DEFAULT (_CMU_IFS_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFS */
-
-/* Bit fields for CMU IFC */
-#define _CMU_IFC_RESETVALUE 0x00000000UL /**< Default value for CMU_IFC */
-#define _CMU_IFC_MASK 0x0000007FUL /**< Mask for CMU_IFC */
-#define CMU_IFC_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFRCORDY_DEFAULT (_CMU_IFC_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY_DEFAULT (_CMU_IFC_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY_DEFAULT (_CMU_IFC_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY_DEFAULT (_CMU_IFC_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY_DEFAULT (_CMU_IFC_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Clear */
-#define _CMU_IFC_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY_DEFAULT (_CMU_IFC_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Clear */
-#define _CMU_IFC_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFC_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFC_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF_DEFAULT (_CMU_IFC_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFC */
-
-/* Bit fields for CMU IEN */
-#define _CMU_IEN_RESETVALUE 0x00000000UL /**< Default value for CMU_IEN */
-#define _CMU_IEN_MASK 0x0000007FUL /**< Mask for CMU_IEN */
-#define CMU_IEN_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Enable */
-#define _CMU_IEN_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFRCORDY_DEFAULT (_CMU_IEN_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Enable */
-#define _CMU_IEN_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY_DEFAULT (_CMU_IEN_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Enable */
-#define _CMU_IEN_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY_DEFAULT (_CMU_IEN_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Enable */
-#define _CMU_IEN_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY_DEFAULT (_CMU_IEN_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Enable */
-#define _CMU_IEN_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY_DEFAULT (_CMU_IEN_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Enable */
-#define _CMU_IEN_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY_DEFAULT (_CMU_IEN_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Enable */
-#define _CMU_IEN_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IEN_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IEN_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF_DEFAULT (_CMU_IEN_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IEN */
-
-/* Bit fields for CMU HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_MASK 0x00000006UL /**< Mask for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA (0x1UL << 1) /**< Direct Memory Access Controller Clock Enable */
-#define _CMU_HFCORECLKEN0_DMA_SHIFT 1 /**< Shift value for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_MASK 0x2UL /**< Bit mask for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA_DEFAULT (_CMU_HFCORECLKEN0_DMA_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE (0x1UL << 2) /**< Low Energy Peripheral Interface Clock Enable */
-#define _CMU_HFCORECLKEN0_LE_SHIFT 2 /**< Shift value for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_MASK 0x4UL /**< Bit mask for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE_DEFAULT (_CMU_HFCORECLKEN0_LE_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-
-/* Bit fields for CMU HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_MASK 0x0000099FUL /**< Mask for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0 (0x1UL << 0) /**< Timer 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER0_SHIFT 0 /**< Shift value for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_MASK 0x1UL /**< Bit mask for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0_DEFAULT (_CMU_HFPERCLKEN0_TIMER0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1 (0x1UL << 1) /**< Timer 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER1_SHIFT 1 /**< Shift value for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_MASK 0x2UL /**< Bit mask for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1_DEFAULT (_CMU_HFPERCLKEN0_TIMER1_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0 (0x1UL << 2) /**< Analog Comparator 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_ACMP0_SHIFT 2 /**< Shift value for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_MASK 0x4UL /**< Bit mask for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0_DEFAULT (_CMU_HFPERCLKEN0_ACMP0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1 (0x1UL << 3) /**< Universal Synchronous/Asynchronous Receiver/Transmitter 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_USART1_SHIFT 3 /**< Shift value for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_MASK 0x8UL /**< Bit mask for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1_DEFAULT (_CMU_HFPERCLKEN0_USART1_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS (0x1UL << 4) /**< Peripheral Reflex System Clock Enable */
-#define _CMU_HFPERCLKEN0_PRS_SHIFT 4 /**< Shift value for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_MASK 0x10UL /**< Bit mask for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS_DEFAULT (_CMU_HFPERCLKEN0_PRS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO (0x1UL << 7) /**< General purpose Input/Output Clock Enable */
-#define _CMU_HFPERCLKEN0_GPIO_SHIFT 7 /**< Shift value for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_MASK 0x80UL /**< Bit mask for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO_DEFAULT (_CMU_HFPERCLKEN0_GPIO_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP (0x1UL << 8) /**< Voltage Comparator Clock Enable */
-#define _CMU_HFPERCLKEN0_VCMP_SHIFT 8 /**< Shift value for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_MASK 0x100UL /**< Bit mask for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP_DEFAULT (_CMU_HFPERCLKEN0_VCMP_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0 (0x1UL << 11) /**< I2C 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_I2C0_SHIFT 11 /**< Shift value for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_MASK 0x800UL /**< Bit mask for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0_DEFAULT (_CMU_HFPERCLKEN0_I2C0_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-
-/* Bit fields for CMU SYNCBUSY */
-#define _CMU_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for CMU_SYNCBUSY */
-#define _CMU_SYNCBUSY_MASK 0x00000055UL /**< Mask for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0 (0x1UL << 0) /**< Low Frequency A Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFACLKEN0_SHIFT 0 /**< Shift value for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_MASK 0x1UL /**< Bit mask for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0_DEFAULT (_CMU_SYNCBUSY_LFACLKEN0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0 (0x1UL << 2) /**< Low Frequency A Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFAPRESC0_SHIFT 2 /**< Shift value for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_MASK 0x4UL /**< Bit mask for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0_DEFAULT (_CMU_SYNCBUSY_LFAPRESC0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0 (0x1UL << 4) /**< Low Frequency B Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFBCLKEN0_SHIFT 4 /**< Shift value for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_MASK 0x10UL /**< Bit mask for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0_DEFAULT (_CMU_SYNCBUSY_LFBCLKEN0_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0 (0x1UL << 6) /**< Low Frequency B Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFBPRESC0_SHIFT 6 /**< Shift value for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_MASK 0x40UL /**< Bit mask for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0_DEFAULT (_CMU_SYNCBUSY_LFBPRESC0_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-
-/* Bit fields for CMU FREEZE */
-#define _CMU_FREEZE_RESETVALUE 0x00000000UL /**< Default value for CMU_FREEZE */
-#define _CMU_FREEZE_MASK 0x00000001UL /**< Mask for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _CMU_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_DEFAULT (_CMU_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_UPDATE (_CMU_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_FREEZE (_CMU_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for CMU_FREEZE */
-
-/* Bit fields for CMU LFACLKEN0 */
-#define _CMU_LFACLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFACLKEN0 */
-#define _CMU_LFACLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC (0x1UL << 0) /**< Real-Time Counter Clock Enable */
-#define _CMU_LFACLKEN0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_MASK 0x1UL /**< Bit mask for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC_DEFAULT (_CMU_LFACLKEN0_RTC_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFACLKEN0 */
-
-/* Bit fields for CMU LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0 (0x1UL << 0) /**< Low Energy UART 0 Clock Enable */
-#define _CMU_LFBCLKEN0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_MASK 0x1UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0_DEFAULT (_CMU_LFBCLKEN0_LEUART0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFBCLKEN0 */
-
-/* Bit fields for CMU LFAPRESC0 */
-#define _CMU_LFAPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_MASK 0x0000000FUL /**< Mask for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_MASK 0xFUL /**< Bit mask for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16 0x00000004UL /**< Mode DIV16 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32 0x00000005UL /**< Mode DIV32 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV64 0x00000006UL /**< Mode DIV64 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV128 0x00000007UL /**< Mode DIV128 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV256 0x00000008UL /**< Mode DIV256 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV512 0x00000009UL /**< Mode DIV512 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV1024 0x0000000AUL /**< Mode DIV1024 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2048 0x0000000BUL /**< Mode DIV2048 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4096 0x0000000CUL /**< Mode DIV4096 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8192 0x0000000DUL /**< Mode DIV8192 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16384 0x0000000EUL /**< Mode DIV16384 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32768 0x0000000FUL /**< Mode DIV32768 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1 (_CMU_LFAPRESC0_RTC_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2 (_CMU_LFAPRESC0_RTC_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4 (_CMU_LFAPRESC0_RTC_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8 (_CMU_LFAPRESC0_RTC_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16 (_CMU_LFAPRESC0_RTC_DIV16 << 0) /**< Shifted mode DIV16 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32 (_CMU_LFAPRESC0_RTC_DIV32 << 0) /**< Shifted mode DIV32 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV64 (_CMU_LFAPRESC0_RTC_DIV64 << 0) /**< Shifted mode DIV64 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV128 (_CMU_LFAPRESC0_RTC_DIV128 << 0) /**< Shifted mode DIV128 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV256 (_CMU_LFAPRESC0_RTC_DIV256 << 0) /**< Shifted mode DIV256 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV512 (_CMU_LFAPRESC0_RTC_DIV512 << 0) /**< Shifted mode DIV512 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1024 (_CMU_LFAPRESC0_RTC_DIV1024 << 0) /**< Shifted mode DIV1024 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2048 (_CMU_LFAPRESC0_RTC_DIV2048 << 0) /**< Shifted mode DIV2048 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4096 (_CMU_LFAPRESC0_RTC_DIV4096 << 0) /**< Shifted mode DIV4096 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8192 (_CMU_LFAPRESC0_RTC_DIV8192 << 0) /**< Shifted mode DIV8192 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16384 (_CMU_LFAPRESC0_RTC_DIV16384 << 0) /**< Shifted mode DIV16384 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32768 (_CMU_LFAPRESC0_RTC_DIV32768 << 0) /**< Shifted mode DIV32768 for CMU_LFAPRESC0 */
-
-/* Bit fields for CMU LFBPRESC0 */
-#define _CMU_LFBPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_MASK 0x00000003UL /**< Mask for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_MASK 0x3UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV1 (_CMU_LFBPRESC0_LEUART0_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV2 (_CMU_LFBPRESC0_LEUART0_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV4 (_CMU_LFBPRESC0_LEUART0_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV8 (_CMU_LFBPRESC0_LEUART0_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFBPRESC0 */
-
-/* Bit fields for CMU PCNTCTRL */
-#define _CMU_PCNTCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_MASK 0x00000003UL /**< Mask for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN (0x1UL << 0) /**< PCNT0 Clock Enable */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_SHIFT 0 /**< Shift value for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_MASK 0x1UL /**< Bit mask for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL (0x1UL << 1) /**< PCNT0 Clock Select */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_SHIFT 1 /**< Shift value for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_MASK 0x2UL /**< Bit mask for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK 0x00000000UL /**< Mode LFACLK for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 0x00000001UL /**< Mode PCNT0S0 for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK (_CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK << 1) /**< Shifted mode LFACLK for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 (_CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 << 1) /**< Shifted mode PCNT0S0 for CMU_PCNTCTRL */
-
-/* Bit fields for CMU ROUTE */
-#define _CMU_ROUTE_RESETVALUE 0x00000000UL /**< Default value for CMU_ROUTE */
-#define _CMU_ROUTE_MASK 0x0000001FUL /**< Mask for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN (0x1UL << 0) /**< CLKOUT0 Pin Enable */
-#define _CMU_ROUTE_CLKOUT0PEN_SHIFT 0 /**< Shift value for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_MASK 0x1UL /**< Bit mask for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN_DEFAULT (_CMU_ROUTE_CLKOUT0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN (0x1UL << 1) /**< CLKOUT1 Pin Enable */
-#define _CMU_ROUTE_CLKOUT1PEN_SHIFT 1 /**< Shift value for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_MASK 0x2UL /**< Bit mask for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN_DEFAULT (_CMU_ROUTE_CLKOUT1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_SHIFT 2 /**< Shift value for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_MASK 0x1CUL /**< Bit mask for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC0 (_CMU_ROUTE_LOCATION_LOC0 << 2) /**< Shifted mode LOC0 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_DEFAULT (_CMU_ROUTE_LOCATION_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC1 (_CMU_ROUTE_LOCATION_LOC1 << 2) /**< Shifted mode LOC1 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC2 (_CMU_ROUTE_LOCATION_LOC2 << 2) /**< Shifted mode LOC2 for CMU_ROUTE */
-
-/* Bit fields for CMU LOCK */
-#define _CMU_LOCK_RESETVALUE 0x00000000UL /**< Default value for CMU_LOCK */
-#define _CMU_LOCK_MASK 0x0000FFFFUL /**< Mask for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCK 0x0000580EUL /**< Mode UNLOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_DEFAULT (_CMU_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCK (_CMU_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCKED (_CMU_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCKED (_CMU_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCK (_CMU_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for CMU_LOCK */
-
-/** @} End of group EFM32ZG108F8_CMU */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_PRS_BitFields EFM32ZG108F8_PRS Bit Fields
- * @{
- ******************************************************************************/
-
-/* Bit fields for PRS SWPULSE */
-#define _PRS_SWPULSE_RESETVALUE 0x00000000UL /**< Default value for PRS_SWPULSE */
-#define _PRS_SWPULSE_MASK 0x0000000FUL /**< Mask for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE (0x1UL << 0) /**< Channel 0 Pulse Generation */
-#define _PRS_SWPULSE_CH0PULSE_SHIFT 0 /**< Shift value for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_MASK 0x1UL /**< Bit mask for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE_DEFAULT (_PRS_SWPULSE_CH0PULSE_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE (0x1UL << 1) /**< Channel 1 Pulse Generation */
-#define _PRS_SWPULSE_CH1PULSE_SHIFT 1 /**< Shift value for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_MASK 0x2UL /**< Bit mask for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE_DEFAULT (_PRS_SWPULSE_CH1PULSE_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE (0x1UL << 2) /**< Channel 2 Pulse Generation */
-#define _PRS_SWPULSE_CH2PULSE_SHIFT 2 /**< Shift value for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_MASK 0x4UL /**< Bit mask for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE_DEFAULT (_PRS_SWPULSE_CH2PULSE_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE (0x1UL << 3) /**< Channel 3 Pulse Generation */
-#define _PRS_SWPULSE_CH3PULSE_SHIFT 3 /**< Shift value for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_MASK 0x8UL /**< Bit mask for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE_DEFAULT (_PRS_SWPULSE_CH3PULSE_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-
-/* Bit fields for PRS SWLEVEL */
-#define _PRS_SWLEVEL_RESETVALUE 0x00000000UL /**< Default value for PRS_SWLEVEL */
-#define _PRS_SWLEVEL_MASK 0x0000000FUL /**< Mask for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL (0x1UL << 0) /**< Channel 0 Software Level */
-#define _PRS_SWLEVEL_CH0LEVEL_SHIFT 0 /**< Shift value for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_MASK 0x1UL /**< Bit mask for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL_DEFAULT (_PRS_SWLEVEL_CH0LEVEL_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL (0x1UL << 1) /**< Channel 1 Software Level */
-#define _PRS_SWLEVEL_CH1LEVEL_SHIFT 1 /**< Shift value for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_MASK 0x2UL /**< Bit mask for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL_DEFAULT (_PRS_SWLEVEL_CH1LEVEL_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL (0x1UL << 2) /**< Channel 2 Software Level */
-#define _PRS_SWLEVEL_CH2LEVEL_SHIFT 2 /**< Shift value for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_MASK 0x4UL /**< Bit mask for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL_DEFAULT (_PRS_SWLEVEL_CH2LEVEL_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL (0x1UL << 3) /**< Channel 3 Software Level */
-#define _PRS_SWLEVEL_CH3LEVEL_SHIFT 3 /**< Shift value for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_MASK 0x8UL /**< Bit mask for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL_DEFAULT (_PRS_SWLEVEL_CH3LEVEL_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-
-/* Bit fields for PRS ROUTE */
-#define _PRS_ROUTE_RESETVALUE 0x00000000UL /**< Default value for PRS_ROUTE */
-#define _PRS_ROUTE_MASK 0x0000070FUL /**< Mask for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN (0x1UL << 0) /**< CH0 Pin Enable */
-#define _PRS_ROUTE_CH0PEN_SHIFT 0 /**< Shift value for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_MASK 0x1UL /**< Bit mask for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN_DEFAULT (_PRS_ROUTE_CH0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN (0x1UL << 1) /**< CH1 Pin Enable */
-#define _PRS_ROUTE_CH1PEN_SHIFT 1 /**< Shift value for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_MASK 0x2UL /**< Bit mask for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN_DEFAULT (_PRS_ROUTE_CH1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN (0x1UL << 2) /**< CH2 Pin Enable */
-#define _PRS_ROUTE_CH2PEN_SHIFT 2 /**< Shift value for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_MASK 0x4UL /**< Bit mask for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN_DEFAULT (_PRS_ROUTE_CH2PEN_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN (0x1UL << 3) /**< CH3 Pin Enable */
-#define _PRS_ROUTE_CH3PEN_SHIFT 3 /**< Shift value for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_MASK 0x8UL /**< Bit mask for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN_DEFAULT (_PRS_ROUTE_CH3PEN_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_SHIFT 8 /**< Shift value for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC0 (_PRS_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_DEFAULT (_PRS_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC1 (_PRS_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC2 (_PRS_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for PRS_ROUTE */
-
-/* Bit fields for PRS CH_CTRL */
-#define _PRS_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_MASK 0x133F0007UL /**< Mask for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_MASK 0x7UL /**< Bit mask for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_VCMPOUT 0x00000000UL /**< Mode VCMPOUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ACMP0OUT 0x00000000UL /**< Mode ACMP0OUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1IRTX 0x00000000UL /**< Mode USART1IRTX for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0UF 0x00000000UL /**< Mode TIMER0UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1UF 0x00000000UL /**< Mode TIMER1UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCOF 0x00000000UL /**< Mode RTCOF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN0 0x00000000UL /**< Mode GPIOPIN0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN8 0x00000000UL /**< Mode GPIOPIN8 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_PCNT0TCC 0x00000000UL /**< Mode PCNT0TCC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1TXC 0x00000001UL /**< Mode USART1TXC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0OF 0x00000001UL /**< Mode TIMER0OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1OF 0x00000001UL /**< Mode TIMER1OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP0 0x00000001UL /**< Mode RTCCOMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN1 0x00000001UL /**< Mode GPIOPIN1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN9 0x00000001UL /**< Mode GPIOPIN9 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000002UL /**< Mode USART1RXDATAV for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC0 0x00000002UL /**< Mode TIMER0CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC0 0x00000002UL /**< Mode TIMER1CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP1 0x00000002UL /**< Mode RTCCOMP1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN2 0x00000002UL /**< Mode GPIOPIN2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN10 0x00000002UL /**< Mode GPIOPIN10 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC1 0x00000003UL /**< Mode TIMER0CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC1 0x00000003UL /**< Mode TIMER1CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN3 0x00000003UL /**< Mode GPIOPIN3 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN11 0x00000003UL /**< Mode GPIOPIN11 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC2 0x00000004UL /**< Mode TIMER0CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC2 0x00000004UL /**< Mode TIMER1CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN4 0x00000004UL /**< Mode GPIOPIN4 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN12 0x00000004UL /**< Mode GPIOPIN12 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN5 0x00000005UL /**< Mode GPIOPIN5 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN13 0x00000005UL /**< Mode GPIOPIN13 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN6 0x00000006UL /**< Mode GPIOPIN6 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN14 0x00000006UL /**< Mode GPIOPIN14 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN7 0x00000007UL /**< Mode GPIOPIN7 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN15 0x00000007UL /**< Mode GPIOPIN15 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_VCMPOUT (_PRS_CH_CTRL_SIGSEL_VCMPOUT << 0) /**< Shifted mode VCMPOUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ACMP0OUT (_PRS_CH_CTRL_SIGSEL_ACMP0OUT << 0) /**< Shifted mode ACMP0OUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1IRTX (_PRS_CH_CTRL_SIGSEL_USART1IRTX << 0) /**< Shifted mode USART1IRTX for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0UF (_PRS_CH_CTRL_SIGSEL_TIMER0UF << 0) /**< Shifted mode TIMER0UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1UF (_PRS_CH_CTRL_SIGSEL_TIMER1UF << 0) /**< Shifted mode TIMER1UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCOF (_PRS_CH_CTRL_SIGSEL_RTCOF << 0) /**< Shifted mode RTCOF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN0 (_PRS_CH_CTRL_SIGSEL_GPIOPIN0 << 0) /**< Shifted mode GPIOPIN0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN8 (_PRS_CH_CTRL_SIGSEL_GPIOPIN8 << 0) /**< Shifted mode GPIOPIN8 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_PCNT0TCC (_PRS_CH_CTRL_SIGSEL_PCNT0TCC << 0) /**< Shifted mode PCNT0TCC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1TXC (_PRS_CH_CTRL_SIGSEL_USART1TXC << 0) /**< Shifted mode USART1TXC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0OF (_PRS_CH_CTRL_SIGSEL_TIMER0OF << 0) /**< Shifted mode TIMER0OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1OF (_PRS_CH_CTRL_SIGSEL_TIMER1OF << 0) /**< Shifted mode TIMER1OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP0 (_PRS_CH_CTRL_SIGSEL_RTCCOMP0 << 0) /**< Shifted mode RTCCOMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN1 (_PRS_CH_CTRL_SIGSEL_GPIOPIN1 << 0) /**< Shifted mode GPIOPIN1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN9 (_PRS_CH_CTRL_SIGSEL_GPIOPIN9 << 0) /**< Shifted mode GPIOPIN9 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1RXDATAV (_PRS_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC0 (_PRS_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC0 (_PRS_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP1 (_PRS_CH_CTRL_SIGSEL_RTCCOMP1 << 0) /**< Shifted mode RTCCOMP1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN2 (_PRS_CH_CTRL_SIGSEL_GPIOPIN2 << 0) /**< Shifted mode GPIOPIN2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN10 (_PRS_CH_CTRL_SIGSEL_GPIOPIN10 << 0) /**< Shifted mode GPIOPIN10 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC1 (_PRS_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC1 (_PRS_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN3 (_PRS_CH_CTRL_SIGSEL_GPIOPIN3 << 0) /**< Shifted mode GPIOPIN3 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN11 (_PRS_CH_CTRL_SIGSEL_GPIOPIN11 << 0) /**< Shifted mode GPIOPIN11 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC2 (_PRS_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC2 (_PRS_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN4 (_PRS_CH_CTRL_SIGSEL_GPIOPIN4 << 0) /**< Shifted mode GPIOPIN4 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN12 (_PRS_CH_CTRL_SIGSEL_GPIOPIN12 << 0) /**< Shifted mode GPIOPIN12 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN5 (_PRS_CH_CTRL_SIGSEL_GPIOPIN5 << 0) /**< Shifted mode GPIOPIN5 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN13 (_PRS_CH_CTRL_SIGSEL_GPIOPIN13 << 0) /**< Shifted mode GPIOPIN13 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN6 (_PRS_CH_CTRL_SIGSEL_GPIOPIN6 << 0) /**< Shifted mode GPIOPIN6 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN14 (_PRS_CH_CTRL_SIGSEL_GPIOPIN14 << 0) /**< Shifted mode GPIOPIN14 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN7 (_PRS_CH_CTRL_SIGSEL_GPIOPIN7 << 0) /**< Shifted mode GPIOPIN7 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN15 (_PRS_CH_CTRL_SIGSEL_GPIOPIN15 << 0) /**< Shifted mode GPIOPIN15 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_VCMP 0x00000001UL /**< Mode VCMP for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_ACMP0 0x00000002UL /**< Mode ACMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_USART1 0x00000011UL /**< Mode USART1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER0 0x0000001CUL /**< Mode TIMER0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER1 0x0000001DUL /**< Mode TIMER1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_RTC 0x00000028UL /**< Mode RTC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOL 0x00000030UL /**< Mode GPIOL for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOH 0x00000031UL /**< Mode GPIOH for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_PCNT0 0x00000036UL /**< Mode PCNT0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_NONE (_PRS_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_VCMP (_PRS_CH_CTRL_SOURCESEL_VCMP << 16) /**< Shifted mode VCMP for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_ACMP0 (_PRS_CH_CTRL_SOURCESEL_ACMP0 << 16) /**< Shifted mode ACMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_USART1 (_PRS_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER0 (_PRS_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER1 (_PRS_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_RTC (_PRS_CH_CTRL_SOURCESEL_RTC << 16) /**< Shifted mode RTC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOL (_PRS_CH_CTRL_SOURCESEL_GPIOL << 16) /**< Shifted mode GPIOL for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOH (_PRS_CH_CTRL_SOURCESEL_GPIOH << 16) /**< Shifted mode GPIOH for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_PCNT0 (_PRS_CH_CTRL_SOURCESEL_PCNT0 << 16) /**< Shifted mode PCNT0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_SHIFT 24 /**< Shift value for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_MASK 0x3000000UL /**< Bit mask for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_OFF 0x00000000UL /**< Mode OFF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_POSEDGE 0x00000001UL /**< Mode POSEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_NEGEDGE 0x00000002UL /**< Mode NEGEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_BOTHEDGES 0x00000003UL /**< Mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_DEFAULT (_PRS_CH_CTRL_EDSEL_DEFAULT << 24) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_OFF (_PRS_CH_CTRL_EDSEL_OFF << 24) /**< Shifted mode OFF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_POSEDGE (_PRS_CH_CTRL_EDSEL_POSEDGE << 24) /**< Shifted mode POSEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_NEGEDGE (_PRS_CH_CTRL_EDSEL_NEGEDGE << 24) /**< Shifted mode NEGEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_BOTHEDGES (_PRS_CH_CTRL_EDSEL_BOTHEDGES << 24) /**< Shifted mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC (0x1UL << 28) /**< Asynchronous reflex */
-#define _PRS_CH_CTRL_ASYNC_SHIFT 28 /**< Shift value for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_MASK 0x10000000UL /**< Bit mask for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC_DEFAULT (_PRS_CH_CTRL_ASYNC_DEFAULT << 28) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-
-/** @} End of group EFM32ZG108F8_PRS */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_UNLOCK EFM32ZG108F8 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG108F8_UNLOCK */
-
-/** @} End of group EFM32ZG108F8_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG108F8_Alternate_Function EFM32ZG108F8 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG108F8_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG108F8 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG108F8_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f16.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f16.h
deleted file mode 100644
index 7dedd56690..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f16.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG110F16
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG110F16_H
-#define EFM32ZG110F16_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16 EFM32ZG110F16
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_Core EFM32ZG110F16 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG110F16_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG110F16_Part EFM32ZG110F16 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG110F16)
-#define EFM32ZG110F16 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG110F16" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG110F16 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00004000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG110F16_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_Peripheral_TypeDefs EFM32ZG110F16 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG110F16_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_Peripheral_Base EFM32ZG110F16 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG110F16_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_Peripheral_Declaration EFM32ZG110F16 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG110F16_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_BitFields EFM32ZG110F16 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_UNLOCK EFM32ZG110F16 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG110F16_UNLOCK */
-
-/** @} End of group EFM32ZG110F16_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F16_Alternate_Function EFM32ZG110F16 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG110F16_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG110F16 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG110F16_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f32.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f32.h
deleted file mode 100644
index 3a27ebb884..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f32.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG110F32
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG110F32_H
-#define EFM32ZG110F32_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32 EFM32ZG110F32
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_Core EFM32ZG110F32 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG110F32_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG110F32_Part EFM32ZG110F32 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG110F32)
-#define EFM32ZG110F32 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG110F32" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG110F32 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00008000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG110F32_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_Peripheral_TypeDefs EFM32ZG110F32 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG110F32_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_Peripheral_Base EFM32ZG110F32 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG110F32_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_Peripheral_Declaration EFM32ZG110F32 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG110F32_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_BitFields EFM32ZG110F32 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_UNLOCK EFM32ZG110F32 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG110F32_UNLOCK */
-
-/** @} End of group EFM32ZG110F32_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F32_Alternate_Function EFM32ZG110F32 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG110F32_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG110F32 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG110F32_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f4.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f4.h
deleted file mode 100644
index 686c998954..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f4.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG110F4
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG110F4_H
-#define EFM32ZG110F4_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4 EFM32ZG110F4
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_Core EFM32ZG110F4 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG110F4_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG110F4_Part EFM32ZG110F4 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG110F4)
-#define EFM32ZG110F4 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG110F4" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG110F4 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00001000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG110F4_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_Peripheral_TypeDefs EFM32ZG110F4 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG110F4_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_Peripheral_Base EFM32ZG110F4 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG110F4_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_Peripheral_Declaration EFM32ZG110F4 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG110F4_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_BitFields EFM32ZG110F4 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_UNLOCK EFM32ZG110F4 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG110F4_UNLOCK */
-
-/** @} End of group EFM32ZG110F4_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F4_Alternate_Function EFM32ZG110F4 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG110F4_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG110F4 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG110F4_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f8.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f8.h
deleted file mode 100644
index 81e3957163..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg110f8.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG110F8
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG110F8_H
-#define EFM32ZG110F8_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8 EFM32ZG110F8
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_Core EFM32ZG110F8 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG110F8_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG110F8_Part EFM32ZG110F8 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG110F8)
-#define EFM32ZG110F8 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG110F8" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG110F8 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00002000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG110F8_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_Peripheral_TypeDefs EFM32ZG110F8 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG110F8_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_Peripheral_Base EFM32ZG110F8 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG110F8_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_Peripheral_Declaration EFM32ZG110F8 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG110F8_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_BitFields EFM32ZG110F8 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_UNLOCK EFM32ZG110F8 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG110F8_UNLOCK */
-
-/** @} End of group EFM32ZG110F8_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG110F8_Alternate_Function EFM32ZG110F8 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG110F8_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG110F8 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG110F8_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f16.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f16.h
deleted file mode 100644
index 20b4acf19d..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f16.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG210F16
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG210F16_H
-#define EFM32ZG210F16_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16 EFM32ZG210F16
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_Core EFM32ZG210F16 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG210F16_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG210F16_Part EFM32ZG210F16 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG210F16)
-#define EFM32ZG210F16 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG210F16" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG210F16 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00004000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG210F16_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_Peripheral_TypeDefs EFM32ZG210F16 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG210F16_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_Peripheral_Base EFM32ZG210F16 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG210F16_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_Peripheral_Declaration EFM32ZG210F16 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG210F16_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_BitFields EFM32ZG210F16 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_UNLOCK EFM32ZG210F16 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG210F16_UNLOCK */
-
-/** @} End of group EFM32ZG210F16_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F16_Alternate_Function EFM32ZG210F16 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG210F16_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG210F16 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG210F16_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f32.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f32.h
deleted file mode 100644
index 6d37586d92..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f32.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG210F32
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG210F32_H
-#define EFM32ZG210F32_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32 EFM32ZG210F32
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_Core EFM32ZG210F32 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG210F32_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG210F32_Part EFM32ZG210F32 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG210F32)
-#define EFM32ZG210F32 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG210F32" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG210F32 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00008000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG210F32_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_Peripheral_TypeDefs EFM32ZG210F32 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG210F32_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_Peripheral_Base EFM32ZG210F32 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG210F32_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_Peripheral_Declaration EFM32ZG210F32 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG210F32_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_BitFields EFM32ZG210F32 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_UNLOCK EFM32ZG210F32 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG210F32_UNLOCK */
-
-/** @} End of group EFM32ZG210F32_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F32_Alternate_Function EFM32ZG210F32 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG210F32_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG210F32 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG210F32_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f4.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f4.h
deleted file mode 100644
index 34a8400323..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f4.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG210F4
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG210F4_H
-#define EFM32ZG210F4_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4 EFM32ZG210F4
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_Core EFM32ZG210F4 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG210F4_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG210F4_Part EFM32ZG210F4 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG210F4)
-#define EFM32ZG210F4 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG210F4" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG210F4 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00001000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG210F4_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_Peripheral_TypeDefs EFM32ZG210F4 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG210F4_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_Peripheral_Base EFM32ZG210F4 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG210F4_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_Peripheral_Declaration EFM32ZG210F4 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG210F4_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_BitFields EFM32ZG210F4 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_UNLOCK EFM32ZG210F4 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG210F4_UNLOCK */
-
-/** @} End of group EFM32ZG210F4_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F4_Alternate_Function EFM32ZG210F4 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG210F4_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG210F4 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG210F4_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f8.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f8.h
deleted file mode 100644
index 1a584ba6b7..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg210f8.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG210F8
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG210F8_H
-#define EFM32ZG210F8_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8 EFM32ZG210F8
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_Core EFM32ZG210F8 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG210F8_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG210F8_Part EFM32ZG210F8 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG210F8)
-#define EFM32ZG210F8 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG210F8" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG210F8 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00002000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG210F8_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_Peripheral_TypeDefs EFM32ZG210F8 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG210F8_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_Peripheral_Base EFM32ZG210F8 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG210F8_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_Peripheral_Declaration EFM32ZG210F8 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG210F8_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_BitFields EFM32ZG210F8 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_UNLOCK EFM32ZG210F8 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG210F8_UNLOCK */
-
-/** @} End of group EFM32ZG210F8_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG210F8_Alternate_Function EFM32ZG210F8 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG210F8_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG210F8 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG210F8_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f16.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f16.h
deleted file mode 100644
index f9a21819a0..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f16.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG222F16
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG222F16_H
-#define EFM32ZG222F16_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16 EFM32ZG222F16
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_Core EFM32ZG222F16 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG222F16_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG222F16_Part EFM32ZG222F16 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG222F16)
-#define EFM32ZG222F16 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG222F16" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG222F16 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00004000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG222F16_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_Peripheral_TypeDefs EFM32ZG222F16 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG222F16_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_Peripheral_Base EFM32ZG222F16 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG222F16_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_Peripheral_Declaration EFM32ZG222F16 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG222F16_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_BitFields EFM32ZG222F16 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_UNLOCK EFM32ZG222F16 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG222F16_UNLOCK */
-
-/** @} End of group EFM32ZG222F16_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F16_Alternate_Function EFM32ZG222F16 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG222F16_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG222F16 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG222F16_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f32.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f32.h
deleted file mode 100644
index 2e87bae657..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f32.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG222F32
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG222F32_H
-#define EFM32ZG222F32_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32 EFM32ZG222F32
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_Core EFM32ZG222F32 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG222F32_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG222F32_Part EFM32ZG222F32 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG222F32)
-#define EFM32ZG222F32 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG222F32" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG222F32 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00008000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00001000UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG222F32_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_Peripheral_TypeDefs EFM32ZG222F32 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG222F32_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_Peripheral_Base EFM32ZG222F32 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG222F32_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_Peripheral_Declaration EFM32ZG222F32 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG222F32_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_BitFields EFM32ZG222F32 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_UNLOCK EFM32ZG222F32 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG222F32_UNLOCK */
-
-/** @} End of group EFM32ZG222F32_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F32_Alternate_Function EFM32ZG222F32 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG222F32_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG222F32 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG222F32_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f4.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f4.h
deleted file mode 100644
index 8926044d9b..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f4.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG222F4
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG222F4_H
-#define EFM32ZG222F4_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4 EFM32ZG222F4
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_Core EFM32ZG222F4 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG222F4_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG222F4_Part EFM32ZG222F4 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG222F4)
-#define EFM32ZG222F4 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG222F4" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG222F4 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00001000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG222F4_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_Peripheral_TypeDefs EFM32ZG222F4 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG222F4_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_Peripheral_Base EFM32ZG222F4 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG222F4_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_Peripheral_Declaration EFM32ZG222F4 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG222F4_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_BitFields EFM32ZG222F4 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_UNLOCK EFM32ZG222F4 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG222F4_UNLOCK */
-
-/** @} End of group EFM32ZG222F4_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F4_Alternate_Function EFM32ZG222F4 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG222F4_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG222F4 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG222F4_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f8.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f8.h
deleted file mode 100644
index 153e9b132e..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg222f8.h
+++ /dev/null
@@ -1,374 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer Header File
- * for EFM32ZG222F8
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-#ifndef EFM32ZG222F8_H
-#define EFM32ZG222F8_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8 EFM32ZG222F8
- * @{
- ******************************************************************************/
-
-/** Interrupt Number Definition */
-typedef enum IRQn{
-/****** Cortex-M0+ Processor Exceptions Numbers *****************************************/
- NonMaskableInt_IRQn = -14, /*!< -14 Cortex-M0+ Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< -13 Cortex-M0+ Hard Fault Interrupt */
- SVCall_IRQn = -5, /*!< -5 Cortex-M0+ SV Call Interrupt */
- PendSV_IRQn = -2, /*!< -2 Cortex-M0+ Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< -1 Cortex-M0+ System Tick Interrupt */
-
-/****** EFM32ZG Peripheral Interrupt Numbers ********************************************/
- DMA_IRQn = 0, /*!< 0 EFM32 DMA Interrupt */
- GPIO_EVEN_IRQn = 1, /*!< 1 EFM32 GPIO_EVEN Interrupt */
- TIMER0_IRQn = 2, /*!< 2 EFM32 TIMER0 Interrupt */
- ACMP0_IRQn = 3, /*!< 3 EFM32 ACMP0 Interrupt */
- ADC0_IRQn = 4, /*!< 4 EFM32 ADC0 Interrupt */
- I2C0_IRQn = 5, /*!< 5 EFM32 I2C0 Interrupt */
- GPIO_ODD_IRQn = 6, /*!< 6 EFM32 GPIO_ODD Interrupt */
- TIMER1_IRQn = 7, /*!< 7 EFM32 TIMER1 Interrupt */
- USART1_RX_IRQn = 8, /*!< 8 EFM32 USART1_RX Interrupt */
- USART1_TX_IRQn = 9, /*!< 9 EFM32 USART1_TX Interrupt */
- LEUART0_IRQn = 10, /*!< 10 EFM32 LEUART0 Interrupt */
- PCNT0_IRQn = 11, /*!< 11 EFM32 PCNT0 Interrupt */
- RTC_IRQn = 12, /*!< 12 EFM32 RTC Interrupt */
- CMU_IRQn = 13, /*!< 13 EFM32 CMU Interrupt */
- VCMP_IRQn = 14, /*!< 14 EFM32 VCMP Interrupt */
- MSC_IRQn = 15, /*!< 15 EFM32 MSC Interrupt */
- AES_IRQn = 16, /*!< 16 EFM32 AES Interrupt */
-} IRQn_Type;
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_Core EFM32ZG222F8 Core
- * @{
- * @brief Processor and Core Peripheral Section
- ******************************************************************************/
-#define __MPU_PRESENT 0U /**< MPU not present */
-#define __VTOR_PRESENT 1U /**< Presence of VTOR register in SCB */
-#define __NVIC_PRIO_BITS 2U /**< NVIC interrupt priority bits */
-#define __Vendor_SysTickConfig 0U /**< Is 1 if different SysTick counter is used */
-
-/** @} End of group EFM32ZG222F8_Core */
-
-/***************************************************************************//**
-* @defgroup EFM32ZG222F8_Part EFM32ZG222F8 Part
-* @{
-*******************************************************************************/
-
-/** Part family */
-#define _EFM32_ZERO_FAMILY 1 /**< Zero Gecko EFM32ZG MCU Family */
-#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */
-#define _SILICON_LABS_32B_SERIES_0 /**< Silicon Labs series number */
-#define _SILICON_LABS_32B_SERIES 0 /**< Silicon Labs series number */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID 76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_GECKO_INTERNAL_SDID_76 /**< Silicon Labs internal use only, may change any time */
-#define _SILICON_LABS_32B_PLATFORM_1 /**< @deprecated Silicon Labs platform name */
-#define _SILICON_LABS_32B_PLATFORM 1 /**< @deprecated Silicon Labs platform name */
-
-/* If part number is not defined as compiler option, define it */
-#if !defined(EFM32ZG222F8)
-#define EFM32ZG222F8 1 /**< Zero Gecko Part */
-#endif
-
-/** Configure part number */
-#define PART_NUMBER "EFM32ZG222F8" /**< Part Number */
-
-/** Memory Base addresses and limits */
-#define FLASH_MEM_BASE (0x0UL) /**< FLASH base address */
-#define FLASH_MEM_SIZE (0x10000000UL) /**< FLASH available address space */
-#define FLASH_MEM_END (0xFFFFFFFUL) /**< FLASH end address */
-#define FLASH_MEM_BITS (0x28UL) /**< FLASH used bits */
-#define AES_MEM_BASE (0x400E0000UL) /**< AES base address */
-#define AES_MEM_SIZE (0x400UL) /**< AES available address space */
-#define AES_MEM_END (0x400E03FFUL) /**< AES end address */
-#define AES_MEM_BITS (0x10UL) /**< AES used bits */
-#define PER_MEM_BASE (0x40000000UL) /**< PER base address */
-#define PER_MEM_SIZE (0xE0000UL) /**< PER available address space */
-#define PER_MEM_END (0x400DFFFFUL) /**< PER end address */
-#define PER_MEM_BITS (0x20UL) /**< PER used bits */
-#define RAM_MEM_BASE (0x20000000UL) /**< RAM base address */
-#define RAM_MEM_SIZE (0x40000UL) /**< RAM available address space */
-#define RAM_MEM_END (0x2003FFFFUL) /**< RAM end address */
-#define RAM_MEM_BITS (0x18UL) /**< RAM used bits */
-#define RAM_CODE_MEM_BASE (0x10000000UL) /**< RAM_CODE base address */
-#define RAM_CODE_MEM_SIZE (0x20000UL) /**< RAM_CODE available address space */
-#define RAM_CODE_MEM_END (0x1001FFFFUL) /**< RAM_CODE end address */
-#define RAM_CODE_MEM_BITS (0x17UL) /**< RAM_CODE used bits */
-
-/** Flash and SRAM limits for EFM32ZG222F8 */
-#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */
-#define FLASH_SIZE (0x00002000UL) /**< Available Flash Memory */
-#define FLASH_PAGE_SIZE 1024U /**< Flash Memory page size */
-#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */
-#define SRAM_SIZE (0x00000800UL) /**< Available SRAM Memory */
-#define __CM0PLUS_REV 0x0001U /**< Cortex-M0+ Core revision r0p1 */
-#define PRS_CHAN_COUNT 4 /**< Number of PRS channels */
-#define DMA_CHAN_COUNT 4 /**< Number of DMA channels */
-#define EXT_IRQ_COUNT 19 /**< Number of External (NVIC) interrupts */
-
-/** AF channels connect the different on-chip peripherals with the af-mux */
-#define AFCHAN_MAX 33U
-#define AFCHANLOC_MAX 7U
-/** Analog AF channels */
-#define AFACHAN_MAX 25U
-
-/* Part number capabilities */
-
-#define TIMER_PRESENT /**< TIMER is available in this part */
-#define TIMER_COUNT 2 /**< 2 TIMERs available */
-#define ACMP_PRESENT /**< ACMP is available in this part */
-#define ACMP_COUNT 1 /**< 1 ACMPs available */
-#define USART_PRESENT /**< USART is available in this part */
-#define USART_COUNT 1 /**< 1 USARTs available */
-#define IDAC_PRESENT /**< IDAC is available in this part */
-#define IDAC_COUNT 1 /**< 1 IDACs available */
-#define ADC_PRESENT /**< ADC is available in this part */
-#define ADC_COUNT 1 /**< 1 ADCs available */
-#define LEUART_PRESENT /**< LEUART is available in this part */
-#define LEUART_COUNT 1 /**< 1 LEUARTs available */
-#define PCNT_PRESENT /**< PCNT is available in this part */
-#define PCNT_COUNT 1 /**< 1 PCNTs available */
-#define I2C_PRESENT /**< I2C is available in this part */
-#define I2C_COUNT 1 /**< 1 I2Cs available */
-#define AES_PRESENT /**< AES is available in this part */
-#define AES_COUNT 1 /**< 1 AES available */
-#define DMA_PRESENT /**< DMA is available in this part */
-#define DMA_COUNT 1 /**< 1 DMA available */
-#define LE_PRESENT /**< LE is available in this part */
-#define LE_COUNT 1 /**< 1 LE available */
-#define MSC_PRESENT /**< MSC is available in this part */
-#define MSC_COUNT 1 /**< 1 MSC available */
-#define EMU_PRESENT /**< EMU is available in this part */
-#define EMU_COUNT 1 /**< 1 EMU available */
-#define RMU_PRESENT /**< RMU is available in this part */
-#define RMU_COUNT 1 /**< 1 RMU available */
-#define CMU_PRESENT /**< CMU is available in this part */
-#define CMU_COUNT 1 /**< 1 CMU available */
-#define PRS_PRESENT /**< PRS is available in this part */
-#define PRS_COUNT 1 /**< 1 PRS available */
-#define GPIO_PRESENT /**< GPIO is available in this part */
-#define GPIO_COUNT 1 /**< 1 GPIO available */
-#define VCMP_PRESENT /**< VCMP is available in this part */
-#define VCMP_COUNT 1 /**< 1 VCMP available */
-#define RTC_PRESENT /**< RTC is available in this part */
-#define RTC_COUNT 1 /**< 1 RTC available */
-#define HFXTAL_PRESENT /**< HFXTAL is available in this part */
-#define HFXTAL_COUNT 1 /**< 1 HFXTAL available */
-#define LFXTAL_PRESENT /**< LFXTAL is available in this part */
-#define LFXTAL_COUNT 1 /**< 1 LFXTAL available */
-#define WDOG_PRESENT /**< WDOG is available in this part */
-#define WDOG_COUNT 1 /**< 1 WDOG available */
-#define DBG_PRESENT /**< DBG is available in this part */
-#define DBG_COUNT 1 /**< 1 DBG available */
-#define BOOTLOADER_PRESENT /**< BOOTLOADER is available in this part */
-#define BOOTLOADER_COUNT 1 /**< 1 BOOTLOADER available */
-#define ANALOG_PRESENT /**< ANALOG is available in this part */
-#define ANALOG_COUNT 1 /**< 1 ANALOG available */
-
-/** @} End of group EFM32ZG222F8_Part */
-
-#define ARM_MATH_CM0PLUS
-#include "arm_math.h" /* To get __CLZ definitions etc. */
-#include "core_cm0plus.h" /* Cortex-M0+ processor and core peripherals */
-#include "system_efm32zg.h" /* System Header */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_Peripheral_TypeDefs EFM32ZG222F8 Peripheral TypeDefs
- * @{
- * @brief Device Specific Peripheral Register Structures
- ******************************************************************************/
-
-#include "efm32zg_aes.h"
-#include "efm32zg_dma_ch.h"
-#include "efm32zg_dma.h"
-#include "efm32zg_msc.h"
-#include "efm32zg_emu.h"
-#include "efm32zg_rmu.h"
-#include "efm32zg_cmu.h"
-#include "efm32zg_timer_cc.h"
-#include "efm32zg_timer.h"
-#include "efm32zg_acmp.h"
-#include "efm32zg_usart.h"
-#include "efm32zg_prs_ch.h"
-#include "efm32zg_prs.h"
-#include "efm32zg_idac.h"
-#include "efm32zg_gpio_p.h"
-#include "efm32zg_gpio.h"
-#include "efm32zg_vcmp.h"
-#include "efm32zg_adc.h"
-#include "efm32zg_leuart.h"
-#include "efm32zg_pcnt.h"
-#include "efm32zg_i2c.h"
-#include "efm32zg_rtc.h"
-#include "efm32zg_wdog.h"
-#include "efm32zg_dma_descriptor.h"
-#include "efm32zg_devinfo.h"
-#include "efm32zg_romtable.h"
-#include "efm32zg_calibrate.h"
-
-/** @} End of group EFM32ZG222F8_Peripheral_TypeDefs */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_Peripheral_Base EFM32ZG222F8 Peripheral Memory Map
- * @{
- ******************************************************************************/
-
-#define AES_BASE (0x400E0000UL) /**< AES base address */
-#define DMA_BASE (0x400C2000UL) /**< DMA base address */
-#define MSC_BASE (0x400C0000UL) /**< MSC base address */
-#define EMU_BASE (0x400C6000UL) /**< EMU base address */
-#define RMU_BASE (0x400CA000UL) /**< RMU base address */
-#define CMU_BASE (0x400C8000UL) /**< CMU base address */
-#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */
-#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */
-#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */
-#define USART1_BASE (0x4000C400UL) /**< USART1 base address */
-#define PRS_BASE (0x400CC000UL) /**< PRS base address */
-#define IDAC0_BASE (0x40004000UL) /**< IDAC0 base address */
-#define GPIO_BASE (0x40006000UL) /**< GPIO base address */
-#define VCMP_BASE (0x40000000UL) /**< VCMP base address */
-#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */
-#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */
-#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */
-#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */
-#define RTC_BASE (0x40080000UL) /**< RTC base address */
-#define WDOG_BASE (0x40088000UL) /**< WDOG base address */
-#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */
-#define DEVINFO_BASE (0x0FE081B0UL) /**< DEVINFO base address */
-#define ROMTABLE_BASE (0xF00FFFD0UL) /**< ROMTABLE base address */
-#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */
-#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */
-
-/** @} End of group EFM32ZG222F8_Peripheral_Base */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_Peripheral_Declaration EFM32ZG222F8 Peripheral Declarations
- * @{
- ******************************************************************************/
-
-#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */
-#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */
-#define MSC ((MSC_TypeDef *) MSC_BASE) /**< MSC base pointer */
-#define EMU ((EMU_TypeDef *) EMU_BASE) /**< EMU base pointer */
-#define RMU ((RMU_TypeDef *) RMU_BASE) /**< RMU base pointer */
-#define CMU ((CMU_TypeDef *) CMU_BASE) /**< CMU base pointer */
-#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */
-#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */
-#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */
-#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */
-#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */
-#define IDAC0 ((IDAC_TypeDef *) IDAC0_BASE) /**< IDAC0 base pointer */
-#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */
-#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */
-#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */
-#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */
-#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */
-#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */
-#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */
-#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */
-#define CALIBRATE ((CALIBRATE_TypeDef *) CALIBRATE_BASE) /**< CALIBRATE base pointer */
-#define DEVINFO ((DEVINFO_TypeDef *) DEVINFO_BASE) /**< DEVINFO base pointer */
-#define ROMTABLE ((ROMTABLE_TypeDef *) ROMTABLE_BASE) /**< ROMTABLE base pointer */
-
-/** @} End of group EFM32ZG222F8_Peripheral_Declaration */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_BitFields EFM32ZG222F8 Bit Fields
- * @{
- ******************************************************************************/
-
-#include "efm32zg_prs_signals.h"
-#include "efm32zg_dmareq.h"
-#include "efm32zg_dmactrl.h"
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_UNLOCK EFM32ZG222F8 Unlock Codes
- * @{
- ******************************************************************************/
-#define MSC_UNLOCK_CODE 0x1B71 /**< MSC unlock code */
-#define EMU_UNLOCK_CODE 0xADE8 /**< EMU unlock code */
-#define CMU_UNLOCK_CODE 0x580E /**< CMU unlock code */
-#define TIMER_UNLOCK_CODE 0xCE80 /**< TIMER unlock code */
-#define GPIO_UNLOCK_CODE 0xA534 /**< GPIO unlock code */
-
-/** @} End of group EFM32ZG222F8_UNLOCK */
-
-/** @} End of group EFM32ZG222F8_BitFields */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG222F8_Alternate_Function EFM32ZG222F8 Alternate Function
- * @{
- ******************************************************************************/
-
-#include "efm32zg_af_ports.h"
-#include "efm32zg_af_pins.h"
-
-/** @} End of group EFM32ZG222F8_Alternate_Function */
-
-/***************************************************************************//**
- * @brief Set the value of a bit field within a register.
- *
- * @param REG
- * The register to update
- * @param MASK
- * The mask for the bit field to update
- * @param VALUE
- * The value to write to the bit field
- * @param OFFSET
- * The number of bits that the field is offset within the register.
- * 0 (zero) means LSB.
- ******************************************************************************/
-#define SET_BIT_FIELD(REG, MASK, VALUE, OFFSET) \
- REG = ((REG) &~(MASK)) | (((VALUE) << (OFFSET)) & (MASK));
-
-/** @} End of group EFM32ZG222F8 */
-
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-#endif /* EFM32ZG222F8_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_acmp.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_acmp.h
deleted file mode 100644
index e3f1557d98..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_acmp.h
+++ /dev/null
@@ -1,334 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_ACMP register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_ACMP
- * @{
- * @brief EFM32ZG_ACMP Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t INPUTSEL; /**< Input Selection Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-} ACMP_TypeDef; /** ACMP Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_ACMP_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for ACMP CTRL */
-#define _ACMP_CTRL_RESETVALUE 0x47000000UL /**< Default value for ACMP_CTRL */
-#define _ACMP_CTRL_MASK 0xCF03077FUL /**< Mask for ACMP_CTRL */
-#define ACMP_CTRL_EN (0x1UL << 0) /**< Analog Comparator Enable */
-#define _ACMP_CTRL_EN_SHIFT 0 /**< Shift value for ACMP_EN */
-#define _ACMP_CTRL_EN_MASK 0x1UL /**< Bit mask for ACMP_EN */
-#define _ACMP_CTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_EN_DEFAULT (_ACMP_CTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_MUXEN (0x1UL << 1) /**< Input Mux Enable */
-#define _ACMP_CTRL_MUXEN_SHIFT 1 /**< Shift value for ACMP_MUXEN */
-#define _ACMP_CTRL_MUXEN_MASK 0x2UL /**< Bit mask for ACMP_MUXEN */
-#define _ACMP_CTRL_MUXEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_MUXEN_DEFAULT (_ACMP_CTRL_MUXEN_DEFAULT << 1) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_INACTVAL (0x1UL << 2) /**< Inactive Value */
-#define _ACMP_CTRL_INACTVAL_SHIFT 2 /**< Shift value for ACMP_INACTVAL */
-#define _ACMP_CTRL_INACTVAL_MASK 0x4UL /**< Bit mask for ACMP_INACTVAL */
-#define _ACMP_CTRL_INACTVAL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define _ACMP_CTRL_INACTVAL_LOW 0x00000000UL /**< Mode LOW for ACMP_CTRL */
-#define _ACMP_CTRL_INACTVAL_HIGH 0x00000001UL /**< Mode HIGH for ACMP_CTRL */
-#define ACMP_CTRL_INACTVAL_DEFAULT (_ACMP_CTRL_INACTVAL_DEFAULT << 2) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_INACTVAL_LOW (_ACMP_CTRL_INACTVAL_LOW << 2) /**< Shifted mode LOW for ACMP_CTRL */
-#define ACMP_CTRL_INACTVAL_HIGH (_ACMP_CTRL_INACTVAL_HIGH << 2) /**< Shifted mode HIGH for ACMP_CTRL */
-#define ACMP_CTRL_GPIOINV (0x1UL << 3) /**< Comparator GPIO Output Invert */
-#define _ACMP_CTRL_GPIOINV_SHIFT 3 /**< Shift value for ACMP_GPIOINV */
-#define _ACMP_CTRL_GPIOINV_MASK 0x8UL /**< Bit mask for ACMP_GPIOINV */
-#define _ACMP_CTRL_GPIOINV_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define _ACMP_CTRL_GPIOINV_NOTINV 0x00000000UL /**< Mode NOTINV for ACMP_CTRL */
-#define _ACMP_CTRL_GPIOINV_INV 0x00000001UL /**< Mode INV for ACMP_CTRL */
-#define ACMP_CTRL_GPIOINV_DEFAULT (_ACMP_CTRL_GPIOINV_DEFAULT << 3) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_GPIOINV_NOTINV (_ACMP_CTRL_GPIOINV_NOTINV << 3) /**< Shifted mode NOTINV for ACMP_CTRL */
-#define ACMP_CTRL_GPIOINV_INV (_ACMP_CTRL_GPIOINV_INV << 3) /**< Shifted mode INV for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_SHIFT 4 /**< Shift value for ACMP_HYSTSEL */
-#define _ACMP_CTRL_HYSTSEL_MASK 0x70UL /**< Bit mask for ACMP_HYSTSEL */
-#define _ACMP_CTRL_HYSTSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST0 0x00000000UL /**< Mode HYST0 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST1 0x00000001UL /**< Mode HYST1 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST2 0x00000002UL /**< Mode HYST2 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST3 0x00000003UL /**< Mode HYST3 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST4 0x00000004UL /**< Mode HYST4 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST5 0x00000005UL /**< Mode HYST5 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST6 0x00000006UL /**< Mode HYST6 for ACMP_CTRL */
-#define _ACMP_CTRL_HYSTSEL_HYST7 0x00000007UL /**< Mode HYST7 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_DEFAULT (_ACMP_CTRL_HYSTSEL_DEFAULT << 4) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST0 (_ACMP_CTRL_HYSTSEL_HYST0 << 4) /**< Shifted mode HYST0 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST1 (_ACMP_CTRL_HYSTSEL_HYST1 << 4) /**< Shifted mode HYST1 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST2 (_ACMP_CTRL_HYSTSEL_HYST2 << 4) /**< Shifted mode HYST2 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST3 (_ACMP_CTRL_HYSTSEL_HYST3 << 4) /**< Shifted mode HYST3 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST4 (_ACMP_CTRL_HYSTSEL_HYST4 << 4) /**< Shifted mode HYST4 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST5 (_ACMP_CTRL_HYSTSEL_HYST5 << 4) /**< Shifted mode HYST5 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST6 (_ACMP_CTRL_HYSTSEL_HYST6 << 4) /**< Shifted mode HYST6 for ACMP_CTRL */
-#define ACMP_CTRL_HYSTSEL_HYST7 (_ACMP_CTRL_HYSTSEL_HYST7 << 4) /**< Shifted mode HYST7 for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_SHIFT 8 /**< Shift value for ACMP_WARMTIME */
-#define _ACMP_CTRL_WARMTIME_MASK 0x700UL /**< Bit mask for ACMP_WARMTIME */
-#define _ACMP_CTRL_WARMTIME_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_4CYCLES 0x00000000UL /**< Mode 4CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_8CYCLES 0x00000001UL /**< Mode 8CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_16CYCLES 0x00000002UL /**< Mode 16CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_32CYCLES 0x00000003UL /**< Mode 32CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_64CYCLES 0x00000004UL /**< Mode 64CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_128CYCLES 0x00000005UL /**< Mode 128CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_256CYCLES 0x00000006UL /**< Mode 256CYCLES for ACMP_CTRL */
-#define _ACMP_CTRL_WARMTIME_512CYCLES 0x00000007UL /**< Mode 512CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_DEFAULT (_ACMP_CTRL_WARMTIME_DEFAULT << 8) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_4CYCLES (_ACMP_CTRL_WARMTIME_4CYCLES << 8) /**< Shifted mode 4CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_8CYCLES (_ACMP_CTRL_WARMTIME_8CYCLES << 8) /**< Shifted mode 8CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_16CYCLES (_ACMP_CTRL_WARMTIME_16CYCLES << 8) /**< Shifted mode 16CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_32CYCLES (_ACMP_CTRL_WARMTIME_32CYCLES << 8) /**< Shifted mode 32CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_64CYCLES (_ACMP_CTRL_WARMTIME_64CYCLES << 8) /**< Shifted mode 64CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_128CYCLES (_ACMP_CTRL_WARMTIME_128CYCLES << 8) /**< Shifted mode 128CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_256CYCLES (_ACMP_CTRL_WARMTIME_256CYCLES << 8) /**< Shifted mode 256CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_WARMTIME_512CYCLES (_ACMP_CTRL_WARMTIME_512CYCLES << 8) /**< Shifted mode 512CYCLES for ACMP_CTRL */
-#define ACMP_CTRL_IRISE (0x1UL << 16) /**< Rising Edge Interrupt Sense */
-#define _ACMP_CTRL_IRISE_SHIFT 16 /**< Shift value for ACMP_IRISE */
-#define _ACMP_CTRL_IRISE_MASK 0x10000UL /**< Bit mask for ACMP_IRISE */
-#define _ACMP_CTRL_IRISE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define _ACMP_CTRL_IRISE_DISABLED 0x00000000UL /**< Mode DISABLED for ACMP_CTRL */
-#define _ACMP_CTRL_IRISE_ENABLED 0x00000001UL /**< Mode ENABLED for ACMP_CTRL */
-#define ACMP_CTRL_IRISE_DEFAULT (_ACMP_CTRL_IRISE_DEFAULT << 16) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_IRISE_DISABLED (_ACMP_CTRL_IRISE_DISABLED << 16) /**< Shifted mode DISABLED for ACMP_CTRL */
-#define ACMP_CTRL_IRISE_ENABLED (_ACMP_CTRL_IRISE_ENABLED << 16) /**< Shifted mode ENABLED for ACMP_CTRL */
-#define ACMP_CTRL_IFALL (0x1UL << 17) /**< Falling Edge Interrupt Sense */
-#define _ACMP_CTRL_IFALL_SHIFT 17 /**< Shift value for ACMP_IFALL */
-#define _ACMP_CTRL_IFALL_MASK 0x20000UL /**< Bit mask for ACMP_IFALL */
-#define _ACMP_CTRL_IFALL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define _ACMP_CTRL_IFALL_DISABLED 0x00000000UL /**< Mode DISABLED for ACMP_CTRL */
-#define _ACMP_CTRL_IFALL_ENABLED 0x00000001UL /**< Mode ENABLED for ACMP_CTRL */
-#define ACMP_CTRL_IFALL_DEFAULT (_ACMP_CTRL_IFALL_DEFAULT << 17) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_IFALL_DISABLED (_ACMP_CTRL_IFALL_DISABLED << 17) /**< Shifted mode DISABLED for ACMP_CTRL */
-#define ACMP_CTRL_IFALL_ENABLED (_ACMP_CTRL_IFALL_ENABLED << 17) /**< Shifted mode ENABLED for ACMP_CTRL */
-#define _ACMP_CTRL_BIASPROG_SHIFT 24 /**< Shift value for ACMP_BIASPROG */
-#define _ACMP_CTRL_BIASPROG_MASK 0xF000000UL /**< Bit mask for ACMP_BIASPROG */
-#define _ACMP_CTRL_BIASPROG_DEFAULT 0x00000007UL /**< Mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_BIASPROG_DEFAULT (_ACMP_CTRL_BIASPROG_DEFAULT << 24) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_HALFBIAS (0x1UL << 30) /**< Half Bias Current */
-#define _ACMP_CTRL_HALFBIAS_SHIFT 30 /**< Shift value for ACMP_HALFBIAS */
-#define _ACMP_CTRL_HALFBIAS_MASK 0x40000000UL /**< Bit mask for ACMP_HALFBIAS */
-#define _ACMP_CTRL_HALFBIAS_DEFAULT 0x00000001UL /**< Mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_HALFBIAS_DEFAULT (_ACMP_CTRL_HALFBIAS_DEFAULT << 30) /**< Shifted mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_FULLBIAS (0x1UL << 31) /**< Full Bias Current */
-#define _ACMP_CTRL_FULLBIAS_SHIFT 31 /**< Shift value for ACMP_FULLBIAS */
-#define _ACMP_CTRL_FULLBIAS_MASK 0x80000000UL /**< Bit mask for ACMP_FULLBIAS */
-#define _ACMP_CTRL_FULLBIAS_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_CTRL */
-#define ACMP_CTRL_FULLBIAS_DEFAULT (_ACMP_CTRL_FULLBIAS_DEFAULT << 31) /**< Shifted mode DEFAULT for ACMP_CTRL */
-
-/* Bit fields for ACMP INPUTSEL */
-#define _ACMP_INPUTSEL_RESETVALUE 0x00010080UL /**< Default value for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_MASK 0x31013FF7UL /**< Mask for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_SHIFT 0 /**< Shift value for ACMP_POSSEL */
-#define _ACMP_INPUTSEL_POSSEL_MASK 0x7UL /**< Bit mask for ACMP_POSSEL */
-#define _ACMP_INPUTSEL_POSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH0 0x00000000UL /**< Mode CH0 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH1 0x00000001UL /**< Mode CH1 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH2 0x00000002UL /**< Mode CH2 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH3 0x00000003UL /**< Mode CH3 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH4 0x00000004UL /**< Mode CH4 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH5 0x00000005UL /**< Mode CH5 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH6 0x00000006UL /**< Mode CH6 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_POSSEL_CH7 0x00000007UL /**< Mode CH7 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_DEFAULT (_ACMP_INPUTSEL_POSSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH0 (_ACMP_INPUTSEL_POSSEL_CH0 << 0) /**< Shifted mode CH0 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH1 (_ACMP_INPUTSEL_POSSEL_CH1 << 0) /**< Shifted mode CH1 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH2 (_ACMP_INPUTSEL_POSSEL_CH2 << 0) /**< Shifted mode CH2 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH3 (_ACMP_INPUTSEL_POSSEL_CH3 << 0) /**< Shifted mode CH3 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH4 (_ACMP_INPUTSEL_POSSEL_CH4 << 0) /**< Shifted mode CH4 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH5 (_ACMP_INPUTSEL_POSSEL_CH5 << 0) /**< Shifted mode CH5 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH6 (_ACMP_INPUTSEL_POSSEL_CH6 << 0) /**< Shifted mode CH6 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_POSSEL_CH7 (_ACMP_INPUTSEL_POSSEL_CH7 << 0) /**< Shifted mode CH7 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_SHIFT 4 /**< Shift value for ACMP_NEGSEL */
-#define _ACMP_INPUTSEL_NEGSEL_MASK 0xF0UL /**< Bit mask for ACMP_NEGSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH0 0x00000000UL /**< Mode CH0 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH1 0x00000001UL /**< Mode CH1 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH2 0x00000002UL /**< Mode CH2 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH3 0x00000003UL /**< Mode CH3 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH4 0x00000004UL /**< Mode CH4 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH5 0x00000005UL /**< Mode CH5 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH6 0x00000006UL /**< Mode CH6 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CH7 0x00000007UL /**< Mode CH7 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_DEFAULT 0x00000008UL /**< Mode DEFAULT for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_1V25 0x00000008UL /**< Mode 1V25 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_2V5 0x00000009UL /**< Mode 2V5 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_VDD 0x0000000AUL /**< Mode VDD for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_NEGSEL_CAPSENSE 0x0000000BUL /**< Mode CAPSENSE for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH0 (_ACMP_INPUTSEL_NEGSEL_CH0 << 4) /**< Shifted mode CH0 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH1 (_ACMP_INPUTSEL_NEGSEL_CH1 << 4) /**< Shifted mode CH1 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH2 (_ACMP_INPUTSEL_NEGSEL_CH2 << 4) /**< Shifted mode CH2 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH3 (_ACMP_INPUTSEL_NEGSEL_CH3 << 4) /**< Shifted mode CH3 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH4 (_ACMP_INPUTSEL_NEGSEL_CH4 << 4) /**< Shifted mode CH4 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH5 (_ACMP_INPUTSEL_NEGSEL_CH5 << 4) /**< Shifted mode CH5 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH6 (_ACMP_INPUTSEL_NEGSEL_CH6 << 4) /**< Shifted mode CH6 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CH7 (_ACMP_INPUTSEL_NEGSEL_CH7 << 4) /**< Shifted mode CH7 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_DEFAULT (_ACMP_INPUTSEL_NEGSEL_DEFAULT << 4) /**< Shifted mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_1V25 (_ACMP_INPUTSEL_NEGSEL_1V25 << 4) /**< Shifted mode 1V25 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_2V5 (_ACMP_INPUTSEL_NEGSEL_2V5 << 4) /**< Shifted mode 2V5 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_VDD (_ACMP_INPUTSEL_NEGSEL_VDD << 4) /**< Shifted mode VDD for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_NEGSEL_CAPSENSE (_ACMP_INPUTSEL_NEGSEL_CAPSENSE << 4) /**< Shifted mode CAPSENSE for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_VDDLEVEL_SHIFT 8 /**< Shift value for ACMP_VDDLEVEL */
-#define _ACMP_INPUTSEL_VDDLEVEL_MASK 0x3F00UL /**< Bit mask for ACMP_VDDLEVEL */
-#define _ACMP_INPUTSEL_VDDLEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_VDDLEVEL_DEFAULT (_ACMP_INPUTSEL_VDDLEVEL_DEFAULT << 8) /**< Shifted mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_LPREF (0x1UL << 16) /**< Low Power Reference Mode */
-#define _ACMP_INPUTSEL_LPREF_SHIFT 16 /**< Shift value for ACMP_LPREF */
-#define _ACMP_INPUTSEL_LPREF_MASK 0x10000UL /**< Bit mask for ACMP_LPREF */
-#define _ACMP_INPUTSEL_LPREF_DEFAULT 0x00000001UL /**< Mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_LPREF_DEFAULT (_ACMP_INPUTSEL_LPREF_DEFAULT << 16) /**< Shifted mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESEN (0x1UL << 24) /**< Capacitive Sense Mode Internal Resistor Enable */
-#define _ACMP_INPUTSEL_CSRESEN_SHIFT 24 /**< Shift value for ACMP_CSRESEN */
-#define _ACMP_INPUTSEL_CSRESEN_MASK 0x1000000UL /**< Bit mask for ACMP_CSRESEN */
-#define _ACMP_INPUTSEL_CSRESEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESEN_DEFAULT (_ACMP_INPUTSEL_CSRESEN_DEFAULT << 24) /**< Shifted mode DEFAULT for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_SHIFT 28 /**< Shift value for ACMP_CSRESSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_MASK 0x30000000UL /**< Bit mask for ACMP_CSRESSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_RES0 0x00000000UL /**< Mode RES0 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_RES1 0x00000001UL /**< Mode RES1 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_RES2 0x00000002UL /**< Mode RES2 for ACMP_INPUTSEL */
-#define _ACMP_INPUTSEL_CSRESSEL_RES3 0x00000003UL /**< Mode RES3 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESSEL_DEFAULT (_ACMP_INPUTSEL_CSRESSEL_DEFAULT << 28) /**< Shifted mode DEFAULT for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESSEL_RES0 (_ACMP_INPUTSEL_CSRESSEL_RES0 << 28) /**< Shifted mode RES0 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESSEL_RES1 (_ACMP_INPUTSEL_CSRESSEL_RES1 << 28) /**< Shifted mode RES1 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESSEL_RES2 (_ACMP_INPUTSEL_CSRESSEL_RES2 << 28) /**< Shifted mode RES2 for ACMP_INPUTSEL */
-#define ACMP_INPUTSEL_CSRESSEL_RES3 (_ACMP_INPUTSEL_CSRESSEL_RES3 << 28) /**< Shifted mode RES3 for ACMP_INPUTSEL */
-
-/* Bit fields for ACMP STATUS */
-#define _ACMP_STATUS_RESETVALUE 0x00000000UL /**< Default value for ACMP_STATUS */
-#define _ACMP_STATUS_MASK 0x00000003UL /**< Mask for ACMP_STATUS */
-#define ACMP_STATUS_ACMPACT (0x1UL << 0) /**< Analog Comparator Active */
-#define _ACMP_STATUS_ACMPACT_SHIFT 0 /**< Shift value for ACMP_ACMPACT */
-#define _ACMP_STATUS_ACMPACT_MASK 0x1UL /**< Bit mask for ACMP_ACMPACT */
-#define _ACMP_STATUS_ACMPACT_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_STATUS */
-#define ACMP_STATUS_ACMPACT_DEFAULT (_ACMP_STATUS_ACMPACT_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_STATUS */
-#define ACMP_STATUS_ACMPOUT (0x1UL << 1) /**< Analog Comparator Output */
-#define _ACMP_STATUS_ACMPOUT_SHIFT 1 /**< Shift value for ACMP_ACMPOUT */
-#define _ACMP_STATUS_ACMPOUT_MASK 0x2UL /**< Bit mask for ACMP_ACMPOUT */
-#define _ACMP_STATUS_ACMPOUT_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_STATUS */
-#define ACMP_STATUS_ACMPOUT_DEFAULT (_ACMP_STATUS_ACMPOUT_DEFAULT << 1) /**< Shifted mode DEFAULT for ACMP_STATUS */
-
-/* Bit fields for ACMP IEN */
-#define _ACMP_IEN_RESETVALUE 0x00000000UL /**< Default value for ACMP_IEN */
-#define _ACMP_IEN_MASK 0x00000003UL /**< Mask for ACMP_IEN */
-#define ACMP_IEN_EDGE (0x1UL << 0) /**< Edge Trigger Interrupt Enable */
-#define _ACMP_IEN_EDGE_SHIFT 0 /**< Shift value for ACMP_EDGE */
-#define _ACMP_IEN_EDGE_MASK 0x1UL /**< Bit mask for ACMP_EDGE */
-#define _ACMP_IEN_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IEN */
-#define ACMP_IEN_EDGE_DEFAULT (_ACMP_IEN_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_IEN */
-#define ACMP_IEN_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Enable */
-#define _ACMP_IEN_WARMUP_SHIFT 1 /**< Shift value for ACMP_WARMUP */
-#define _ACMP_IEN_WARMUP_MASK 0x2UL /**< Bit mask for ACMP_WARMUP */
-#define _ACMP_IEN_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IEN */
-#define ACMP_IEN_WARMUP_DEFAULT (_ACMP_IEN_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for ACMP_IEN */
-
-/* Bit fields for ACMP IF */
-#define _ACMP_IF_RESETVALUE 0x00000000UL /**< Default value for ACMP_IF */
-#define _ACMP_IF_MASK 0x00000003UL /**< Mask for ACMP_IF */
-#define ACMP_IF_EDGE (0x1UL << 0) /**< Edge Triggered Interrupt Flag */
-#define _ACMP_IF_EDGE_SHIFT 0 /**< Shift value for ACMP_EDGE */
-#define _ACMP_IF_EDGE_MASK 0x1UL /**< Bit mask for ACMP_EDGE */
-#define _ACMP_IF_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IF */
-#define ACMP_IF_EDGE_DEFAULT (_ACMP_IF_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_IF */
-#define ACMP_IF_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Flag */
-#define _ACMP_IF_WARMUP_SHIFT 1 /**< Shift value for ACMP_WARMUP */
-#define _ACMP_IF_WARMUP_MASK 0x2UL /**< Bit mask for ACMP_WARMUP */
-#define _ACMP_IF_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IF */
-#define ACMP_IF_WARMUP_DEFAULT (_ACMP_IF_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for ACMP_IF */
-
-/* Bit fields for ACMP IFS */
-#define _ACMP_IFS_RESETVALUE 0x00000000UL /**< Default value for ACMP_IFS */
-#define _ACMP_IFS_MASK 0x00000003UL /**< Mask for ACMP_IFS */
-#define ACMP_IFS_EDGE (0x1UL << 0) /**< Edge Triggered Interrupt Flag Set */
-#define _ACMP_IFS_EDGE_SHIFT 0 /**< Shift value for ACMP_EDGE */
-#define _ACMP_IFS_EDGE_MASK 0x1UL /**< Bit mask for ACMP_EDGE */
-#define _ACMP_IFS_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IFS */
-#define ACMP_IFS_EDGE_DEFAULT (_ACMP_IFS_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_IFS */
-#define ACMP_IFS_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Flag Set */
-#define _ACMP_IFS_WARMUP_SHIFT 1 /**< Shift value for ACMP_WARMUP */
-#define _ACMP_IFS_WARMUP_MASK 0x2UL /**< Bit mask for ACMP_WARMUP */
-#define _ACMP_IFS_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IFS */
-#define ACMP_IFS_WARMUP_DEFAULT (_ACMP_IFS_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for ACMP_IFS */
-
-/* Bit fields for ACMP IFC */
-#define _ACMP_IFC_RESETVALUE 0x00000000UL /**< Default value for ACMP_IFC */
-#define _ACMP_IFC_MASK 0x00000003UL /**< Mask for ACMP_IFC */
-#define ACMP_IFC_EDGE (0x1UL << 0) /**< Edge Triggered Interrupt Flag Clear */
-#define _ACMP_IFC_EDGE_SHIFT 0 /**< Shift value for ACMP_EDGE */
-#define _ACMP_IFC_EDGE_MASK 0x1UL /**< Bit mask for ACMP_EDGE */
-#define _ACMP_IFC_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IFC */
-#define ACMP_IFC_EDGE_DEFAULT (_ACMP_IFC_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_IFC */
-#define ACMP_IFC_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Flag Clear */
-#define _ACMP_IFC_WARMUP_SHIFT 1 /**< Shift value for ACMP_WARMUP */
-#define _ACMP_IFC_WARMUP_MASK 0x2UL /**< Bit mask for ACMP_WARMUP */
-#define _ACMP_IFC_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_IFC */
-#define ACMP_IFC_WARMUP_DEFAULT (_ACMP_IFC_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for ACMP_IFC */
-
-/* Bit fields for ACMP ROUTE */
-#define _ACMP_ROUTE_RESETVALUE 0x00000000UL /**< Default value for ACMP_ROUTE */
-#define _ACMP_ROUTE_MASK 0x00000701UL /**< Mask for ACMP_ROUTE */
-#define ACMP_ROUTE_ACMPPEN (0x1UL << 0) /**< ACMP Output Pin Enable */
-#define _ACMP_ROUTE_ACMPPEN_SHIFT 0 /**< Shift value for ACMP_ACMPPEN */
-#define _ACMP_ROUTE_ACMPPEN_MASK 0x1UL /**< Bit mask for ACMP_ACMPPEN */
-#define _ACMP_ROUTE_ACMPPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_ROUTE */
-#define ACMP_ROUTE_ACMPPEN_DEFAULT (_ACMP_ROUTE_ACMPPEN_DEFAULT << 0) /**< Shifted mode DEFAULT for ACMP_ROUTE */
-#define _ACMP_ROUTE_LOCATION_SHIFT 8 /**< Shift value for ACMP_LOCATION */
-#define _ACMP_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for ACMP_LOCATION */
-#define _ACMP_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for ACMP_ROUTE */
-#define _ACMP_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for ACMP_ROUTE */
-#define _ACMP_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for ACMP_ROUTE */
-#define _ACMP_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for ACMP_ROUTE */
-#define ACMP_ROUTE_LOCATION_LOC0 (_ACMP_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for ACMP_ROUTE */
-#define ACMP_ROUTE_LOCATION_DEFAULT (_ACMP_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for ACMP_ROUTE */
-#define ACMP_ROUTE_LOCATION_LOC1 (_ACMP_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for ACMP_ROUTE */
-#define ACMP_ROUTE_LOCATION_LOC2 (_ACMP_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for ACMP_ROUTE */
-
-/** @} End of group EFM32ZG_ACMP */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_adc.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_adc.h
deleted file mode 100644
index f7c2cdcf35..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_adc.h
+++ /dev/null
@@ -1,654 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_ADC register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_ADC
- * @{
- * @brief EFM32ZG_ADC Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t SINGLECTRL; /**< Single Sample Control Register */
- __IOM uint32_t SCANCTRL; /**< Scan Control Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IM uint32_t SINGLEDATA; /**< Single Conversion Result Data */
- __IM uint32_t SCANDATA; /**< Scan Conversion Result Data */
- __IM uint32_t SINGLEDATAP; /**< Single Conversion Result Data Peek Register */
- __IM uint32_t SCANDATAP; /**< Scan Sequence Result Data Peek Register */
- __IOM uint32_t CAL; /**< Calibration Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved for future use **/
- __IOM uint32_t BIASPROG; /**< Bias Programming Register */
-} ADC_TypeDef; /** ADC Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_ADC_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for ADC CTRL */
-#define _ADC_CTRL_RESETVALUE 0x001F0000UL /**< Default value for ADC_CTRL */
-#define _ADC_CTRL_MASK 0x1F7F7F3BUL /**< Mask for ADC_CTRL */
-#define _ADC_CTRL_WARMUPMODE_SHIFT 0 /**< Shift value for ADC_WARMUPMODE */
-#define _ADC_CTRL_WARMUPMODE_MASK 0x3UL /**< Bit mask for ADC_WARMUPMODE */
-#define _ADC_CTRL_WARMUPMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_WARMUPMODE_NORMAL 0x00000000UL /**< Mode NORMAL for ADC_CTRL */
-#define _ADC_CTRL_WARMUPMODE_FASTBG 0x00000001UL /**< Mode FASTBG for ADC_CTRL */
-#define _ADC_CTRL_WARMUPMODE_KEEPSCANREFWARM 0x00000002UL /**< Mode KEEPSCANREFWARM for ADC_CTRL */
-#define _ADC_CTRL_WARMUPMODE_KEEPADCWARM 0x00000003UL /**< Mode KEEPADCWARM for ADC_CTRL */
-#define ADC_CTRL_WARMUPMODE_DEFAULT (_ADC_CTRL_WARMUPMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_WARMUPMODE_NORMAL (_ADC_CTRL_WARMUPMODE_NORMAL << 0) /**< Shifted mode NORMAL for ADC_CTRL */
-#define ADC_CTRL_WARMUPMODE_FASTBG (_ADC_CTRL_WARMUPMODE_FASTBG << 0) /**< Shifted mode FASTBG for ADC_CTRL */
-#define ADC_CTRL_WARMUPMODE_KEEPSCANREFWARM (_ADC_CTRL_WARMUPMODE_KEEPSCANREFWARM << 0) /**< Shifted mode KEEPSCANREFWARM for ADC_CTRL */
-#define ADC_CTRL_WARMUPMODE_KEEPADCWARM (_ADC_CTRL_WARMUPMODE_KEEPADCWARM << 0) /**< Shifted mode KEEPADCWARM for ADC_CTRL */
-#define ADC_CTRL_TAILGATE (0x1UL << 3) /**< Conversion Tailgating */
-#define _ADC_CTRL_TAILGATE_SHIFT 3 /**< Shift value for ADC_TAILGATE */
-#define _ADC_CTRL_TAILGATE_MASK 0x8UL /**< Bit mask for ADC_TAILGATE */
-#define _ADC_CTRL_TAILGATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_TAILGATE_DEFAULT (_ADC_CTRL_TAILGATE_DEFAULT << 3) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_LPFMODE_SHIFT 4 /**< Shift value for ADC_LPFMODE */
-#define _ADC_CTRL_LPFMODE_MASK 0x30UL /**< Bit mask for ADC_LPFMODE */
-#define _ADC_CTRL_LPFMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_LPFMODE_BYPASS 0x00000000UL /**< Mode BYPASS for ADC_CTRL */
-#define _ADC_CTRL_LPFMODE_DECAP 0x00000001UL /**< Mode DECAP for ADC_CTRL */
-#define _ADC_CTRL_LPFMODE_RCFILT 0x00000002UL /**< Mode RCFILT for ADC_CTRL */
-#define ADC_CTRL_LPFMODE_DEFAULT (_ADC_CTRL_LPFMODE_DEFAULT << 4) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_LPFMODE_BYPASS (_ADC_CTRL_LPFMODE_BYPASS << 4) /**< Shifted mode BYPASS for ADC_CTRL */
-#define ADC_CTRL_LPFMODE_DECAP (_ADC_CTRL_LPFMODE_DECAP << 4) /**< Shifted mode DECAP for ADC_CTRL */
-#define ADC_CTRL_LPFMODE_RCFILT (_ADC_CTRL_LPFMODE_RCFILT << 4) /**< Shifted mode RCFILT for ADC_CTRL */
-#define _ADC_CTRL_PRESC_SHIFT 8 /**< Shift value for ADC_PRESC */
-#define _ADC_CTRL_PRESC_MASK 0x7F00UL /**< Bit mask for ADC_PRESC */
-#define _ADC_CTRL_PRESC_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_PRESC_NODIVISION 0x00000000UL /**< Mode NODIVISION for ADC_CTRL */
-#define ADC_CTRL_PRESC_DEFAULT (_ADC_CTRL_PRESC_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_PRESC_NODIVISION (_ADC_CTRL_PRESC_NODIVISION << 8) /**< Shifted mode NODIVISION for ADC_CTRL */
-#define _ADC_CTRL_TIMEBASE_SHIFT 16 /**< Shift value for ADC_TIMEBASE */
-#define _ADC_CTRL_TIMEBASE_MASK 0x7F0000UL /**< Bit mask for ADC_TIMEBASE */
-#define _ADC_CTRL_TIMEBASE_DEFAULT 0x0000001FUL /**< Mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_TIMEBASE_DEFAULT (_ADC_CTRL_TIMEBASE_DEFAULT << 16) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_SHIFT 24 /**< Shift value for ADC_OVSRSEL */
-#define _ADC_CTRL_OVSRSEL_MASK 0xF000000UL /**< Bit mask for ADC_OVSRSEL */
-#define _ADC_CTRL_OVSRSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X2 0x00000000UL /**< Mode X2 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X4 0x00000001UL /**< Mode X4 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X8 0x00000002UL /**< Mode X8 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X16 0x00000003UL /**< Mode X16 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X32 0x00000004UL /**< Mode X32 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X64 0x00000005UL /**< Mode X64 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X128 0x00000006UL /**< Mode X128 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X256 0x00000007UL /**< Mode X256 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X512 0x00000008UL /**< Mode X512 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X1024 0x00000009UL /**< Mode X1024 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X2048 0x0000000AUL /**< Mode X2048 for ADC_CTRL */
-#define _ADC_CTRL_OVSRSEL_X4096 0x0000000BUL /**< Mode X4096 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_DEFAULT (_ADC_CTRL_OVSRSEL_DEFAULT << 24) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X2 (_ADC_CTRL_OVSRSEL_X2 << 24) /**< Shifted mode X2 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X4 (_ADC_CTRL_OVSRSEL_X4 << 24) /**< Shifted mode X4 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X8 (_ADC_CTRL_OVSRSEL_X8 << 24) /**< Shifted mode X8 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X16 (_ADC_CTRL_OVSRSEL_X16 << 24) /**< Shifted mode X16 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X32 (_ADC_CTRL_OVSRSEL_X32 << 24) /**< Shifted mode X32 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X64 (_ADC_CTRL_OVSRSEL_X64 << 24) /**< Shifted mode X64 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X128 (_ADC_CTRL_OVSRSEL_X128 << 24) /**< Shifted mode X128 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X256 (_ADC_CTRL_OVSRSEL_X256 << 24) /**< Shifted mode X256 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X512 (_ADC_CTRL_OVSRSEL_X512 << 24) /**< Shifted mode X512 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X1024 (_ADC_CTRL_OVSRSEL_X1024 << 24) /**< Shifted mode X1024 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X2048 (_ADC_CTRL_OVSRSEL_X2048 << 24) /**< Shifted mode X2048 for ADC_CTRL */
-#define ADC_CTRL_OVSRSEL_X4096 (_ADC_CTRL_OVSRSEL_X4096 << 24) /**< Shifted mode X4096 for ADC_CTRL */
-#define ADC_CTRL_CHCONIDLE (0x1UL << 28) /**< Input channel connected when ADC is IDLE */
-#define _ADC_CTRL_CHCONIDLE_SHIFT 28 /**< Shift value for ADC_CHCONIDLE */
-#define _ADC_CTRL_CHCONIDLE_MASK 0x10000000UL /**< Bit mask for ADC_CHCONIDLE */
-#define _ADC_CTRL_CHCONIDLE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CTRL */
-#define _ADC_CTRL_CHCONIDLE_DISCONNECT 0x00000000UL /**< Mode DISCONNECT for ADC_CTRL */
-#define _ADC_CTRL_CHCONIDLE_KEEPCON 0x00000001UL /**< Mode KEEPCON for ADC_CTRL */
-#define ADC_CTRL_CHCONIDLE_DEFAULT (_ADC_CTRL_CHCONIDLE_DEFAULT << 28) /**< Shifted mode DEFAULT for ADC_CTRL */
-#define ADC_CTRL_CHCONIDLE_DISCONNECT (_ADC_CTRL_CHCONIDLE_DISCONNECT << 28) /**< Shifted mode DISCONNECT for ADC_CTRL */
-#define ADC_CTRL_CHCONIDLE_KEEPCON (_ADC_CTRL_CHCONIDLE_KEEPCON << 28) /**< Shifted mode KEEPCON for ADC_CTRL */
-
-/* Bit fields for ADC CMD */
-#define _ADC_CMD_RESETVALUE 0x00000000UL /**< Default value for ADC_CMD */
-#define _ADC_CMD_MASK 0x0000000FUL /**< Mask for ADC_CMD */
-#define ADC_CMD_SINGLESTART (0x1UL << 0) /**< Single Conversion Start */
-#define _ADC_CMD_SINGLESTART_SHIFT 0 /**< Shift value for ADC_SINGLESTART */
-#define _ADC_CMD_SINGLESTART_MASK 0x1UL /**< Bit mask for ADC_SINGLESTART */
-#define _ADC_CMD_SINGLESTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SINGLESTART_DEFAULT (_ADC_CMD_SINGLESTART_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SINGLESTOP (0x1UL << 1) /**< Single Conversion Stop */
-#define _ADC_CMD_SINGLESTOP_SHIFT 1 /**< Shift value for ADC_SINGLESTOP */
-#define _ADC_CMD_SINGLESTOP_MASK 0x2UL /**< Bit mask for ADC_SINGLESTOP */
-#define _ADC_CMD_SINGLESTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SINGLESTOP_DEFAULT (_ADC_CMD_SINGLESTOP_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SCANSTART (0x1UL << 2) /**< Scan Sequence Start */
-#define _ADC_CMD_SCANSTART_SHIFT 2 /**< Shift value for ADC_SCANSTART */
-#define _ADC_CMD_SCANSTART_MASK 0x4UL /**< Bit mask for ADC_SCANSTART */
-#define _ADC_CMD_SCANSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SCANSTART_DEFAULT (_ADC_CMD_SCANSTART_DEFAULT << 2) /**< Shifted mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SCANSTOP (0x1UL << 3) /**< Scan Sequence Stop */
-#define _ADC_CMD_SCANSTOP_SHIFT 3 /**< Shift value for ADC_SCANSTOP */
-#define _ADC_CMD_SCANSTOP_MASK 0x8UL /**< Bit mask for ADC_SCANSTOP */
-#define _ADC_CMD_SCANSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CMD */
-#define ADC_CMD_SCANSTOP_DEFAULT (_ADC_CMD_SCANSTOP_DEFAULT << 3) /**< Shifted mode DEFAULT for ADC_CMD */
-
-/* Bit fields for ADC STATUS */
-#define _ADC_STATUS_RESETVALUE 0x00000000UL /**< Default value for ADC_STATUS */
-#define _ADC_STATUS_MASK 0x07031303UL /**< Mask for ADC_STATUS */
-#define ADC_STATUS_SINGLEACT (0x1UL << 0) /**< Single Conversion Active */
-#define _ADC_STATUS_SINGLEACT_SHIFT 0 /**< Shift value for ADC_SINGLEACT */
-#define _ADC_STATUS_SINGLEACT_MASK 0x1UL /**< Bit mask for ADC_SINGLEACT */
-#define _ADC_STATUS_SINGLEACT_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SINGLEACT_DEFAULT (_ADC_STATUS_SINGLEACT_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANACT (0x1UL << 1) /**< Scan Conversion Active */
-#define _ADC_STATUS_SCANACT_SHIFT 1 /**< Shift value for ADC_SCANACT */
-#define _ADC_STATUS_SCANACT_MASK 0x2UL /**< Bit mask for ADC_SCANACT */
-#define _ADC_STATUS_SCANACT_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANACT_DEFAULT (_ADC_STATUS_SCANACT_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SINGLEREFWARM (0x1UL << 8) /**< Single Reference Warmed Up */
-#define _ADC_STATUS_SINGLEREFWARM_SHIFT 8 /**< Shift value for ADC_SINGLEREFWARM */
-#define _ADC_STATUS_SINGLEREFWARM_MASK 0x100UL /**< Bit mask for ADC_SINGLEREFWARM */
-#define _ADC_STATUS_SINGLEREFWARM_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SINGLEREFWARM_DEFAULT (_ADC_STATUS_SINGLEREFWARM_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANREFWARM (0x1UL << 9) /**< Scan Reference Warmed Up */
-#define _ADC_STATUS_SCANREFWARM_SHIFT 9 /**< Shift value for ADC_SCANREFWARM */
-#define _ADC_STATUS_SCANREFWARM_MASK 0x200UL /**< Bit mask for ADC_SCANREFWARM */
-#define _ADC_STATUS_SCANREFWARM_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANREFWARM_DEFAULT (_ADC_STATUS_SCANREFWARM_DEFAULT << 9) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_WARM (0x1UL << 12) /**< ADC Warmed Up */
-#define _ADC_STATUS_WARM_SHIFT 12 /**< Shift value for ADC_WARM */
-#define _ADC_STATUS_WARM_MASK 0x1000UL /**< Bit mask for ADC_WARM */
-#define _ADC_STATUS_WARM_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_WARM_DEFAULT (_ADC_STATUS_WARM_DEFAULT << 12) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SINGLEDV (0x1UL << 16) /**< Single Sample Data Valid */
-#define _ADC_STATUS_SINGLEDV_SHIFT 16 /**< Shift value for ADC_SINGLEDV */
-#define _ADC_STATUS_SINGLEDV_MASK 0x10000UL /**< Bit mask for ADC_SINGLEDV */
-#define _ADC_STATUS_SINGLEDV_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SINGLEDV_DEFAULT (_ADC_STATUS_SINGLEDV_DEFAULT << 16) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANDV (0x1UL << 17) /**< Scan Data Valid */
-#define _ADC_STATUS_SCANDV_SHIFT 17 /**< Shift value for ADC_SCANDV */
-#define _ADC_STATUS_SCANDV_MASK 0x20000UL /**< Bit mask for ADC_SCANDV */
-#define _ADC_STATUS_SCANDV_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANDV_DEFAULT (_ADC_STATUS_SCANDV_DEFAULT << 17) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_SHIFT 24 /**< Shift value for ADC_SCANDATASRC */
-#define _ADC_STATUS_SCANDATASRC_MASK 0x7000000UL /**< Bit mask for ADC_SCANDATASRC */
-#define _ADC_STATUS_SCANDATASRC_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH0 0x00000000UL /**< Mode CH0 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH1 0x00000001UL /**< Mode CH1 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH2 0x00000002UL /**< Mode CH2 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH3 0x00000003UL /**< Mode CH3 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH4 0x00000004UL /**< Mode CH4 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH5 0x00000005UL /**< Mode CH5 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH6 0x00000006UL /**< Mode CH6 for ADC_STATUS */
-#define _ADC_STATUS_SCANDATASRC_CH7 0x00000007UL /**< Mode CH7 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_DEFAULT (_ADC_STATUS_SCANDATASRC_DEFAULT << 24) /**< Shifted mode DEFAULT for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH0 (_ADC_STATUS_SCANDATASRC_CH0 << 24) /**< Shifted mode CH0 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH1 (_ADC_STATUS_SCANDATASRC_CH1 << 24) /**< Shifted mode CH1 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH2 (_ADC_STATUS_SCANDATASRC_CH2 << 24) /**< Shifted mode CH2 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH3 (_ADC_STATUS_SCANDATASRC_CH3 << 24) /**< Shifted mode CH3 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH4 (_ADC_STATUS_SCANDATASRC_CH4 << 24) /**< Shifted mode CH4 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH5 (_ADC_STATUS_SCANDATASRC_CH5 << 24) /**< Shifted mode CH5 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH6 (_ADC_STATUS_SCANDATASRC_CH6 << 24) /**< Shifted mode CH6 for ADC_STATUS */
-#define ADC_STATUS_SCANDATASRC_CH7 (_ADC_STATUS_SCANDATASRC_CH7 << 24) /**< Shifted mode CH7 for ADC_STATUS */
-
-/* Bit fields for ADC SINGLECTRL */
-#define _ADC_SINGLECTRL_RESETVALUE 0x00000000UL /**< Default value for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_MASK 0x31F70F37UL /**< Mask for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REP (0x1UL << 0) /**< Single Sample Repetitive Mode */
-#define _ADC_SINGLECTRL_REP_SHIFT 0 /**< Shift value for ADC_REP */
-#define _ADC_SINGLECTRL_REP_MASK 0x1UL /**< Bit mask for ADC_REP */
-#define _ADC_SINGLECTRL_REP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REP_DEFAULT (_ADC_SINGLECTRL_REP_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_DIFF (0x1UL << 1) /**< Single Sample Differential Mode */
-#define _ADC_SINGLECTRL_DIFF_SHIFT 1 /**< Shift value for ADC_DIFF */
-#define _ADC_SINGLECTRL_DIFF_MASK 0x2UL /**< Bit mask for ADC_DIFF */
-#define _ADC_SINGLECTRL_DIFF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_DIFF_DEFAULT (_ADC_SINGLECTRL_DIFF_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_ADJ (0x1UL << 2) /**< Single Sample Result Adjustment */
-#define _ADC_SINGLECTRL_ADJ_SHIFT 2 /**< Shift value for ADC_ADJ */
-#define _ADC_SINGLECTRL_ADJ_MASK 0x4UL /**< Bit mask for ADC_ADJ */
-#define _ADC_SINGLECTRL_ADJ_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_ADJ_RIGHT 0x00000000UL /**< Mode RIGHT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_ADJ_LEFT 0x00000001UL /**< Mode LEFT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_ADJ_DEFAULT (_ADC_SINGLECTRL_ADJ_DEFAULT << 2) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_ADJ_RIGHT (_ADC_SINGLECTRL_ADJ_RIGHT << 2) /**< Shifted mode RIGHT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_ADJ_LEFT (_ADC_SINGLECTRL_ADJ_LEFT << 2) /**< Shifted mode LEFT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_RES_SHIFT 4 /**< Shift value for ADC_RES */
-#define _ADC_SINGLECTRL_RES_MASK 0x30UL /**< Bit mask for ADC_RES */
-#define _ADC_SINGLECTRL_RES_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_RES_12BIT 0x00000000UL /**< Mode 12BIT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_RES_8BIT 0x00000001UL /**< Mode 8BIT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_RES_6BIT 0x00000002UL /**< Mode 6BIT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_RES_OVS 0x00000003UL /**< Mode OVS for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_RES_DEFAULT (_ADC_SINGLECTRL_RES_DEFAULT << 4) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_RES_12BIT (_ADC_SINGLECTRL_RES_12BIT << 4) /**< Shifted mode 12BIT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_RES_8BIT (_ADC_SINGLECTRL_RES_8BIT << 4) /**< Shifted mode 8BIT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_RES_6BIT (_ADC_SINGLECTRL_RES_6BIT << 4) /**< Shifted mode 6BIT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_RES_OVS (_ADC_SINGLECTRL_RES_OVS << 4) /**< Shifted mode OVS for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_SHIFT 8 /**< Shift value for ADC_INPUTSEL */
-#define _ADC_SINGLECTRL_INPUTSEL_MASK 0xF00UL /**< Bit mask for ADC_INPUTSEL */
-#define _ADC_SINGLECTRL_INPUTSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH0 0x00000000UL /**< Mode CH0 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH0CH1 0x00000000UL /**< Mode CH0CH1 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH1 0x00000001UL /**< Mode CH1 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH2CH3 0x00000001UL /**< Mode CH2CH3 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH2 0x00000002UL /**< Mode CH2 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH4CH5 0x00000002UL /**< Mode CH4CH5 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH6CH7 0x00000003UL /**< Mode CH6CH7 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH3 0x00000003UL /**< Mode CH3 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH4 0x00000004UL /**< Mode CH4 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_DIFF0 0x00000004UL /**< Mode DIFF0 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH5 0x00000005UL /**< Mode CH5 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH6 0x00000006UL /**< Mode CH6 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_CH7 0x00000007UL /**< Mode CH7 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_TEMP 0x00000008UL /**< Mode TEMP for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_VDDDIV3 0x00000009UL /**< Mode VDDDIV3 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_VDD 0x0000000AUL /**< Mode VDD for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_VSS 0x0000000BUL /**< Mode VSS for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_VREFDIV2 0x0000000CUL /**< Mode VREFDIV2 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_DAC0OUT0 0x0000000DUL /**< Mode DAC0OUT0 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_INPUTSEL_DAC0OUT1 0x0000000EUL /**< Mode DAC0OUT1 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_DEFAULT (_ADC_SINGLECTRL_INPUTSEL_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH0 (_ADC_SINGLECTRL_INPUTSEL_CH0 << 8) /**< Shifted mode CH0 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH0CH1 (_ADC_SINGLECTRL_INPUTSEL_CH0CH1 << 8) /**< Shifted mode CH0CH1 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH1 (_ADC_SINGLECTRL_INPUTSEL_CH1 << 8) /**< Shifted mode CH1 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH2CH3 (_ADC_SINGLECTRL_INPUTSEL_CH2CH3 << 8) /**< Shifted mode CH2CH3 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH2 (_ADC_SINGLECTRL_INPUTSEL_CH2 << 8) /**< Shifted mode CH2 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH4CH5 (_ADC_SINGLECTRL_INPUTSEL_CH4CH5 << 8) /**< Shifted mode CH4CH5 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH6CH7 (_ADC_SINGLECTRL_INPUTSEL_CH6CH7 << 8) /**< Shifted mode CH6CH7 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH3 (_ADC_SINGLECTRL_INPUTSEL_CH3 << 8) /**< Shifted mode CH3 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH4 (_ADC_SINGLECTRL_INPUTSEL_CH4 << 8) /**< Shifted mode CH4 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_DIFF0 (_ADC_SINGLECTRL_INPUTSEL_DIFF0 << 8) /**< Shifted mode DIFF0 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH5 (_ADC_SINGLECTRL_INPUTSEL_CH5 << 8) /**< Shifted mode CH5 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH6 (_ADC_SINGLECTRL_INPUTSEL_CH6 << 8) /**< Shifted mode CH6 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_CH7 (_ADC_SINGLECTRL_INPUTSEL_CH7 << 8) /**< Shifted mode CH7 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_TEMP (_ADC_SINGLECTRL_INPUTSEL_TEMP << 8) /**< Shifted mode TEMP for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_VDDDIV3 (_ADC_SINGLECTRL_INPUTSEL_VDDDIV3 << 8) /**< Shifted mode VDDDIV3 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_VDD (_ADC_SINGLECTRL_INPUTSEL_VDD << 8) /**< Shifted mode VDD for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_VSS (_ADC_SINGLECTRL_INPUTSEL_VSS << 8) /**< Shifted mode VSS for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_VREFDIV2 (_ADC_SINGLECTRL_INPUTSEL_VREFDIV2 << 8) /**< Shifted mode VREFDIV2 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_DAC0OUT0 (_ADC_SINGLECTRL_INPUTSEL_DAC0OUT0 << 8) /**< Shifted mode DAC0OUT0 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_INPUTSEL_DAC0OUT1 (_ADC_SINGLECTRL_INPUTSEL_DAC0OUT1 << 8) /**< Shifted mode DAC0OUT1 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_SHIFT 16 /**< Shift value for ADC_REF */
-#define _ADC_SINGLECTRL_REF_MASK 0x70000UL /**< Bit mask for ADC_REF */
-#define _ADC_SINGLECTRL_REF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_1V25 0x00000000UL /**< Mode 1V25 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_2V5 0x00000001UL /**< Mode 2V5 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_VDD 0x00000002UL /**< Mode VDD for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_5VDIFF 0x00000003UL /**< Mode 5VDIFF for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_EXTSINGLE 0x00000004UL /**< Mode EXTSINGLE for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_2XEXTDIFF 0x00000005UL /**< Mode 2XEXTDIFF for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_REF_2XVDD 0x00000006UL /**< Mode 2XVDD for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_DEFAULT (_ADC_SINGLECTRL_REF_DEFAULT << 16) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_1V25 (_ADC_SINGLECTRL_REF_1V25 << 16) /**< Shifted mode 1V25 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_2V5 (_ADC_SINGLECTRL_REF_2V5 << 16) /**< Shifted mode 2V5 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_VDD (_ADC_SINGLECTRL_REF_VDD << 16) /**< Shifted mode VDD for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_5VDIFF (_ADC_SINGLECTRL_REF_5VDIFF << 16) /**< Shifted mode 5VDIFF for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_EXTSINGLE (_ADC_SINGLECTRL_REF_EXTSINGLE << 16) /**< Shifted mode EXTSINGLE for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_2XEXTDIFF (_ADC_SINGLECTRL_REF_2XEXTDIFF << 16) /**< Shifted mode 2XEXTDIFF for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_REF_2XVDD (_ADC_SINGLECTRL_REF_2XVDD << 16) /**< Shifted mode 2XVDD for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_SHIFT 20 /**< Shift value for ADC_AT */
-#define _ADC_SINGLECTRL_AT_MASK 0xF00000UL /**< Bit mask for ADC_AT */
-#define _ADC_SINGLECTRL_AT_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_1CYCLE 0x00000000UL /**< Mode 1CYCLE for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_2CYCLES 0x00000001UL /**< Mode 2CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_4CYCLES 0x00000002UL /**< Mode 4CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_8CYCLES 0x00000003UL /**< Mode 8CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_16CYCLES 0x00000004UL /**< Mode 16CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_32CYCLES 0x00000005UL /**< Mode 32CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_64CYCLES 0x00000006UL /**< Mode 64CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_128CYCLES 0x00000007UL /**< Mode 128CYCLES for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_AT_256CYCLES 0x00000008UL /**< Mode 256CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_DEFAULT (_ADC_SINGLECTRL_AT_DEFAULT << 20) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_1CYCLE (_ADC_SINGLECTRL_AT_1CYCLE << 20) /**< Shifted mode 1CYCLE for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_2CYCLES (_ADC_SINGLECTRL_AT_2CYCLES << 20) /**< Shifted mode 2CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_4CYCLES (_ADC_SINGLECTRL_AT_4CYCLES << 20) /**< Shifted mode 4CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_8CYCLES (_ADC_SINGLECTRL_AT_8CYCLES << 20) /**< Shifted mode 8CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_16CYCLES (_ADC_SINGLECTRL_AT_16CYCLES << 20) /**< Shifted mode 16CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_32CYCLES (_ADC_SINGLECTRL_AT_32CYCLES << 20) /**< Shifted mode 32CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_64CYCLES (_ADC_SINGLECTRL_AT_64CYCLES << 20) /**< Shifted mode 64CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_128CYCLES (_ADC_SINGLECTRL_AT_128CYCLES << 20) /**< Shifted mode 128CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_AT_256CYCLES (_ADC_SINGLECTRL_AT_256CYCLES << 20) /**< Shifted mode 256CYCLES for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSEN (0x1UL << 24) /**< Single Sample PRS Trigger Enable */
-#define _ADC_SINGLECTRL_PRSEN_SHIFT 24 /**< Shift value for ADC_PRSEN */
-#define _ADC_SINGLECTRL_PRSEN_MASK 0x1000000UL /**< Bit mask for ADC_PRSEN */
-#define _ADC_SINGLECTRL_PRSEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSEN_DEFAULT (_ADC_SINGLECTRL_PRSEN_DEFAULT << 24) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_PRSSEL_SHIFT 28 /**< Shift value for ADC_PRSSEL */
-#define _ADC_SINGLECTRL_PRSSEL_MASK 0x30000000UL /**< Bit mask for ADC_PRSSEL */
-#define _ADC_SINGLECTRL_PRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_PRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_PRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_PRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for ADC_SINGLECTRL */
-#define _ADC_SINGLECTRL_PRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSSEL_DEFAULT (_ADC_SINGLECTRL_PRSSEL_DEFAULT << 28) /**< Shifted mode DEFAULT for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSSEL_PRSCH0 (_ADC_SINGLECTRL_PRSSEL_PRSCH0 << 28) /**< Shifted mode PRSCH0 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSSEL_PRSCH1 (_ADC_SINGLECTRL_PRSSEL_PRSCH1 << 28) /**< Shifted mode PRSCH1 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSSEL_PRSCH2 (_ADC_SINGLECTRL_PRSSEL_PRSCH2 << 28) /**< Shifted mode PRSCH2 for ADC_SINGLECTRL */
-#define ADC_SINGLECTRL_PRSSEL_PRSCH3 (_ADC_SINGLECTRL_PRSSEL_PRSCH3 << 28) /**< Shifted mode PRSCH3 for ADC_SINGLECTRL */
-
-/* Bit fields for ADC SCANCTRL */
-#define _ADC_SCANCTRL_RESETVALUE 0x00000000UL /**< Default value for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_MASK 0x31F7FF37UL /**< Mask for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REP (0x1UL << 0) /**< Scan Sequence Repetitive Mode */
-#define _ADC_SCANCTRL_REP_SHIFT 0 /**< Shift value for ADC_REP */
-#define _ADC_SCANCTRL_REP_MASK 0x1UL /**< Bit mask for ADC_REP */
-#define _ADC_SCANCTRL_REP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REP_DEFAULT (_ADC_SCANCTRL_REP_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_DIFF (0x1UL << 1) /**< Scan Sequence Differential Mode */
-#define _ADC_SCANCTRL_DIFF_SHIFT 1 /**< Shift value for ADC_DIFF */
-#define _ADC_SCANCTRL_DIFF_MASK 0x2UL /**< Bit mask for ADC_DIFF */
-#define _ADC_SCANCTRL_DIFF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_DIFF_DEFAULT (_ADC_SCANCTRL_DIFF_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_ADJ (0x1UL << 2) /**< Scan Sequence Result Adjustment */
-#define _ADC_SCANCTRL_ADJ_SHIFT 2 /**< Shift value for ADC_ADJ */
-#define _ADC_SCANCTRL_ADJ_MASK 0x4UL /**< Bit mask for ADC_ADJ */
-#define _ADC_SCANCTRL_ADJ_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_ADJ_RIGHT 0x00000000UL /**< Mode RIGHT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_ADJ_LEFT 0x00000001UL /**< Mode LEFT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_ADJ_DEFAULT (_ADC_SCANCTRL_ADJ_DEFAULT << 2) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_ADJ_RIGHT (_ADC_SCANCTRL_ADJ_RIGHT << 2) /**< Shifted mode RIGHT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_ADJ_LEFT (_ADC_SCANCTRL_ADJ_LEFT << 2) /**< Shifted mode LEFT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_RES_SHIFT 4 /**< Shift value for ADC_RES */
-#define _ADC_SCANCTRL_RES_MASK 0x30UL /**< Bit mask for ADC_RES */
-#define _ADC_SCANCTRL_RES_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_RES_12BIT 0x00000000UL /**< Mode 12BIT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_RES_8BIT 0x00000001UL /**< Mode 8BIT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_RES_6BIT 0x00000002UL /**< Mode 6BIT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_RES_OVS 0x00000003UL /**< Mode OVS for ADC_SCANCTRL */
-#define ADC_SCANCTRL_RES_DEFAULT (_ADC_SCANCTRL_RES_DEFAULT << 4) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_RES_12BIT (_ADC_SCANCTRL_RES_12BIT << 4) /**< Shifted mode 12BIT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_RES_8BIT (_ADC_SCANCTRL_RES_8BIT << 4) /**< Shifted mode 8BIT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_RES_6BIT (_ADC_SCANCTRL_RES_6BIT << 4) /**< Shifted mode 6BIT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_RES_OVS (_ADC_SCANCTRL_RES_OVS << 4) /**< Shifted mode OVS for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_SHIFT 8 /**< Shift value for ADC_INPUTMASK */
-#define _ADC_SCANCTRL_INPUTMASK_MASK 0xFF00UL /**< Bit mask for ADC_INPUTMASK */
-#define _ADC_SCANCTRL_INPUTMASK_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH0 0x00000001UL /**< Mode CH0 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH0CH1 0x00000001UL /**< Mode CH0CH1 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH1 0x00000002UL /**< Mode CH1 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH2CH3 0x00000002UL /**< Mode CH2CH3 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH2 0x00000004UL /**< Mode CH2 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH4CH5 0x00000004UL /**< Mode CH4CH5 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH6CH7 0x00000008UL /**< Mode CH6CH7 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH3 0x00000008UL /**< Mode CH3 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH4 0x00000010UL /**< Mode CH4 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH5 0x00000020UL /**< Mode CH5 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH6 0x00000040UL /**< Mode CH6 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_INPUTMASK_CH7 0x00000080UL /**< Mode CH7 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_DEFAULT (_ADC_SCANCTRL_INPUTMASK_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH0 (_ADC_SCANCTRL_INPUTMASK_CH0 << 8) /**< Shifted mode CH0 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH0CH1 (_ADC_SCANCTRL_INPUTMASK_CH0CH1 << 8) /**< Shifted mode CH0CH1 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH1 (_ADC_SCANCTRL_INPUTMASK_CH1 << 8) /**< Shifted mode CH1 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH2CH3 (_ADC_SCANCTRL_INPUTMASK_CH2CH3 << 8) /**< Shifted mode CH2CH3 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH2 (_ADC_SCANCTRL_INPUTMASK_CH2 << 8) /**< Shifted mode CH2 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH4CH5 (_ADC_SCANCTRL_INPUTMASK_CH4CH5 << 8) /**< Shifted mode CH4CH5 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH6CH7 (_ADC_SCANCTRL_INPUTMASK_CH6CH7 << 8) /**< Shifted mode CH6CH7 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH3 (_ADC_SCANCTRL_INPUTMASK_CH3 << 8) /**< Shifted mode CH3 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH4 (_ADC_SCANCTRL_INPUTMASK_CH4 << 8) /**< Shifted mode CH4 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH5 (_ADC_SCANCTRL_INPUTMASK_CH5 << 8) /**< Shifted mode CH5 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH6 (_ADC_SCANCTRL_INPUTMASK_CH6 << 8) /**< Shifted mode CH6 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_INPUTMASK_CH7 (_ADC_SCANCTRL_INPUTMASK_CH7 << 8) /**< Shifted mode CH7 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_SHIFT 16 /**< Shift value for ADC_REF */
-#define _ADC_SCANCTRL_REF_MASK 0x70000UL /**< Bit mask for ADC_REF */
-#define _ADC_SCANCTRL_REF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_1V25 0x00000000UL /**< Mode 1V25 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_2V5 0x00000001UL /**< Mode 2V5 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_VDD 0x00000002UL /**< Mode VDD for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_5VDIFF 0x00000003UL /**< Mode 5VDIFF for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_EXTSINGLE 0x00000004UL /**< Mode EXTSINGLE for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_2XEXTDIFF 0x00000005UL /**< Mode 2XEXTDIFF for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_REF_2XVDD 0x00000006UL /**< Mode 2XVDD for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_DEFAULT (_ADC_SCANCTRL_REF_DEFAULT << 16) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_1V25 (_ADC_SCANCTRL_REF_1V25 << 16) /**< Shifted mode 1V25 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_2V5 (_ADC_SCANCTRL_REF_2V5 << 16) /**< Shifted mode 2V5 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_VDD (_ADC_SCANCTRL_REF_VDD << 16) /**< Shifted mode VDD for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_5VDIFF (_ADC_SCANCTRL_REF_5VDIFF << 16) /**< Shifted mode 5VDIFF for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_EXTSINGLE (_ADC_SCANCTRL_REF_EXTSINGLE << 16) /**< Shifted mode EXTSINGLE for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_2XEXTDIFF (_ADC_SCANCTRL_REF_2XEXTDIFF << 16) /**< Shifted mode 2XEXTDIFF for ADC_SCANCTRL */
-#define ADC_SCANCTRL_REF_2XVDD (_ADC_SCANCTRL_REF_2XVDD << 16) /**< Shifted mode 2XVDD for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_SHIFT 20 /**< Shift value for ADC_AT */
-#define _ADC_SCANCTRL_AT_MASK 0xF00000UL /**< Bit mask for ADC_AT */
-#define _ADC_SCANCTRL_AT_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_1CYCLE 0x00000000UL /**< Mode 1CYCLE for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_2CYCLES 0x00000001UL /**< Mode 2CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_4CYCLES 0x00000002UL /**< Mode 4CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_8CYCLES 0x00000003UL /**< Mode 8CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_16CYCLES 0x00000004UL /**< Mode 16CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_32CYCLES 0x00000005UL /**< Mode 32CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_64CYCLES 0x00000006UL /**< Mode 64CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_128CYCLES 0x00000007UL /**< Mode 128CYCLES for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_AT_256CYCLES 0x00000008UL /**< Mode 256CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_DEFAULT (_ADC_SCANCTRL_AT_DEFAULT << 20) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_1CYCLE (_ADC_SCANCTRL_AT_1CYCLE << 20) /**< Shifted mode 1CYCLE for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_2CYCLES (_ADC_SCANCTRL_AT_2CYCLES << 20) /**< Shifted mode 2CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_4CYCLES (_ADC_SCANCTRL_AT_4CYCLES << 20) /**< Shifted mode 4CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_8CYCLES (_ADC_SCANCTRL_AT_8CYCLES << 20) /**< Shifted mode 8CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_16CYCLES (_ADC_SCANCTRL_AT_16CYCLES << 20) /**< Shifted mode 16CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_32CYCLES (_ADC_SCANCTRL_AT_32CYCLES << 20) /**< Shifted mode 32CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_64CYCLES (_ADC_SCANCTRL_AT_64CYCLES << 20) /**< Shifted mode 64CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_128CYCLES (_ADC_SCANCTRL_AT_128CYCLES << 20) /**< Shifted mode 128CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_AT_256CYCLES (_ADC_SCANCTRL_AT_256CYCLES << 20) /**< Shifted mode 256CYCLES for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSEN (0x1UL << 24) /**< Scan Sequence PRS Trigger Enable */
-#define _ADC_SCANCTRL_PRSEN_SHIFT 24 /**< Shift value for ADC_PRSEN */
-#define _ADC_SCANCTRL_PRSEN_MASK 0x1000000UL /**< Bit mask for ADC_PRSEN */
-#define _ADC_SCANCTRL_PRSEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSEN_DEFAULT (_ADC_SCANCTRL_PRSEN_DEFAULT << 24) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_PRSSEL_SHIFT 28 /**< Shift value for ADC_PRSSEL */
-#define _ADC_SCANCTRL_PRSSEL_MASK 0x30000000UL /**< Bit mask for ADC_PRSSEL */
-#define _ADC_SCANCTRL_PRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_PRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_PRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_PRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for ADC_SCANCTRL */
-#define _ADC_SCANCTRL_PRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSSEL_DEFAULT (_ADC_SCANCTRL_PRSSEL_DEFAULT << 28) /**< Shifted mode DEFAULT for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSSEL_PRSCH0 (_ADC_SCANCTRL_PRSSEL_PRSCH0 << 28) /**< Shifted mode PRSCH0 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSSEL_PRSCH1 (_ADC_SCANCTRL_PRSSEL_PRSCH1 << 28) /**< Shifted mode PRSCH1 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSSEL_PRSCH2 (_ADC_SCANCTRL_PRSSEL_PRSCH2 << 28) /**< Shifted mode PRSCH2 for ADC_SCANCTRL */
-#define ADC_SCANCTRL_PRSSEL_PRSCH3 (_ADC_SCANCTRL_PRSSEL_PRSCH3 << 28) /**< Shifted mode PRSCH3 for ADC_SCANCTRL */
-
-/* Bit fields for ADC IEN */
-#define _ADC_IEN_RESETVALUE 0x00000000UL /**< Default value for ADC_IEN */
-#define _ADC_IEN_MASK 0x00000303UL /**< Mask for ADC_IEN */
-#define ADC_IEN_SINGLE (0x1UL << 0) /**< Single Conversion Complete Interrupt Enable */
-#define _ADC_IEN_SINGLE_SHIFT 0 /**< Shift value for ADC_SINGLE */
-#define _ADC_IEN_SINGLE_MASK 0x1UL /**< Bit mask for ADC_SINGLE */
-#define _ADC_IEN_SINGLE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SINGLE_DEFAULT (_ADC_IEN_SINGLE_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SCAN (0x1UL << 1) /**< Scan Conversion Complete Interrupt Enable */
-#define _ADC_IEN_SCAN_SHIFT 1 /**< Shift value for ADC_SCAN */
-#define _ADC_IEN_SCAN_MASK 0x2UL /**< Bit mask for ADC_SCAN */
-#define _ADC_IEN_SCAN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SCAN_DEFAULT (_ADC_IEN_SCAN_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SINGLEOF (0x1UL << 8) /**< Single Result Overflow Interrupt Enable */
-#define _ADC_IEN_SINGLEOF_SHIFT 8 /**< Shift value for ADC_SINGLEOF */
-#define _ADC_IEN_SINGLEOF_MASK 0x100UL /**< Bit mask for ADC_SINGLEOF */
-#define _ADC_IEN_SINGLEOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SINGLEOF_DEFAULT (_ADC_IEN_SINGLEOF_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SCANOF (0x1UL << 9) /**< Scan Result Overflow Interrupt Enable */
-#define _ADC_IEN_SCANOF_SHIFT 9 /**< Shift value for ADC_SCANOF */
-#define _ADC_IEN_SCANOF_MASK 0x200UL /**< Bit mask for ADC_SCANOF */
-#define _ADC_IEN_SCANOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IEN */
-#define ADC_IEN_SCANOF_DEFAULT (_ADC_IEN_SCANOF_DEFAULT << 9) /**< Shifted mode DEFAULT for ADC_IEN */
-
-/* Bit fields for ADC IF */
-#define _ADC_IF_RESETVALUE 0x00000000UL /**< Default value for ADC_IF */
-#define _ADC_IF_MASK 0x00000303UL /**< Mask for ADC_IF */
-#define ADC_IF_SINGLE (0x1UL << 0) /**< Single Conversion Complete Interrupt Flag */
-#define _ADC_IF_SINGLE_SHIFT 0 /**< Shift value for ADC_SINGLE */
-#define _ADC_IF_SINGLE_MASK 0x1UL /**< Bit mask for ADC_SINGLE */
-#define _ADC_IF_SINGLE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IF */
-#define ADC_IF_SINGLE_DEFAULT (_ADC_IF_SINGLE_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_IF */
-#define ADC_IF_SCAN (0x1UL << 1) /**< Scan Conversion Complete Interrupt Flag */
-#define _ADC_IF_SCAN_SHIFT 1 /**< Shift value for ADC_SCAN */
-#define _ADC_IF_SCAN_MASK 0x2UL /**< Bit mask for ADC_SCAN */
-#define _ADC_IF_SCAN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IF */
-#define ADC_IF_SCAN_DEFAULT (_ADC_IF_SCAN_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_IF */
-#define ADC_IF_SINGLEOF (0x1UL << 8) /**< Single Result Overflow Interrupt Flag */
-#define _ADC_IF_SINGLEOF_SHIFT 8 /**< Shift value for ADC_SINGLEOF */
-#define _ADC_IF_SINGLEOF_MASK 0x100UL /**< Bit mask for ADC_SINGLEOF */
-#define _ADC_IF_SINGLEOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IF */
-#define ADC_IF_SINGLEOF_DEFAULT (_ADC_IF_SINGLEOF_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_IF */
-#define ADC_IF_SCANOF (0x1UL << 9) /**< Scan Result Overflow Interrupt Flag */
-#define _ADC_IF_SCANOF_SHIFT 9 /**< Shift value for ADC_SCANOF */
-#define _ADC_IF_SCANOF_MASK 0x200UL /**< Bit mask for ADC_SCANOF */
-#define _ADC_IF_SCANOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IF */
-#define ADC_IF_SCANOF_DEFAULT (_ADC_IF_SCANOF_DEFAULT << 9) /**< Shifted mode DEFAULT for ADC_IF */
-
-/* Bit fields for ADC IFS */
-#define _ADC_IFS_RESETVALUE 0x00000000UL /**< Default value for ADC_IFS */
-#define _ADC_IFS_MASK 0x00000303UL /**< Mask for ADC_IFS */
-#define ADC_IFS_SINGLE (0x1UL << 0) /**< Single Conversion Complete Interrupt Flag Set */
-#define _ADC_IFS_SINGLE_SHIFT 0 /**< Shift value for ADC_SINGLE */
-#define _ADC_IFS_SINGLE_MASK 0x1UL /**< Bit mask for ADC_SINGLE */
-#define _ADC_IFS_SINGLE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SINGLE_DEFAULT (_ADC_IFS_SINGLE_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SCAN (0x1UL << 1) /**< Scan Conversion Complete Interrupt Flag Set */
-#define _ADC_IFS_SCAN_SHIFT 1 /**< Shift value for ADC_SCAN */
-#define _ADC_IFS_SCAN_MASK 0x2UL /**< Bit mask for ADC_SCAN */
-#define _ADC_IFS_SCAN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SCAN_DEFAULT (_ADC_IFS_SCAN_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SINGLEOF (0x1UL << 8) /**< Single Result Overflow Interrupt Flag Set */
-#define _ADC_IFS_SINGLEOF_SHIFT 8 /**< Shift value for ADC_SINGLEOF */
-#define _ADC_IFS_SINGLEOF_MASK 0x100UL /**< Bit mask for ADC_SINGLEOF */
-#define _ADC_IFS_SINGLEOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SINGLEOF_DEFAULT (_ADC_IFS_SINGLEOF_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SCANOF (0x1UL << 9) /**< Scan Result Overflow Interrupt Flag Set */
-#define _ADC_IFS_SCANOF_SHIFT 9 /**< Shift value for ADC_SCANOF */
-#define _ADC_IFS_SCANOF_MASK 0x200UL /**< Bit mask for ADC_SCANOF */
-#define _ADC_IFS_SCANOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFS */
-#define ADC_IFS_SCANOF_DEFAULT (_ADC_IFS_SCANOF_DEFAULT << 9) /**< Shifted mode DEFAULT for ADC_IFS */
-
-/* Bit fields for ADC IFC */
-#define _ADC_IFC_RESETVALUE 0x00000000UL /**< Default value for ADC_IFC */
-#define _ADC_IFC_MASK 0x00000303UL /**< Mask for ADC_IFC */
-#define ADC_IFC_SINGLE (0x1UL << 0) /**< Single Conversion Complete Interrupt Flag Clear */
-#define _ADC_IFC_SINGLE_SHIFT 0 /**< Shift value for ADC_SINGLE */
-#define _ADC_IFC_SINGLE_MASK 0x1UL /**< Bit mask for ADC_SINGLE */
-#define _ADC_IFC_SINGLE_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SINGLE_DEFAULT (_ADC_IFC_SINGLE_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SCAN (0x1UL << 1) /**< Scan Conversion Complete Interrupt Flag Clear */
-#define _ADC_IFC_SCAN_SHIFT 1 /**< Shift value for ADC_SCAN */
-#define _ADC_IFC_SCAN_MASK 0x2UL /**< Bit mask for ADC_SCAN */
-#define _ADC_IFC_SCAN_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SCAN_DEFAULT (_ADC_IFC_SCAN_DEFAULT << 1) /**< Shifted mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SINGLEOF (0x1UL << 8) /**< Single Result Overflow Interrupt Flag Clear */
-#define _ADC_IFC_SINGLEOF_SHIFT 8 /**< Shift value for ADC_SINGLEOF */
-#define _ADC_IFC_SINGLEOF_MASK 0x100UL /**< Bit mask for ADC_SINGLEOF */
-#define _ADC_IFC_SINGLEOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SINGLEOF_DEFAULT (_ADC_IFC_SINGLEOF_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SCANOF (0x1UL << 9) /**< Scan Result Overflow Interrupt Flag Clear */
-#define _ADC_IFC_SCANOF_SHIFT 9 /**< Shift value for ADC_SCANOF */
-#define _ADC_IFC_SCANOF_MASK 0x200UL /**< Bit mask for ADC_SCANOF */
-#define _ADC_IFC_SCANOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_IFC */
-#define ADC_IFC_SCANOF_DEFAULT (_ADC_IFC_SCANOF_DEFAULT << 9) /**< Shifted mode DEFAULT for ADC_IFC */
-
-/* Bit fields for ADC SINGLEDATA */
-#define _ADC_SINGLEDATA_RESETVALUE 0x00000000UL /**< Default value for ADC_SINGLEDATA */
-#define _ADC_SINGLEDATA_MASK 0xFFFFFFFFUL /**< Mask for ADC_SINGLEDATA */
-#define _ADC_SINGLEDATA_DATA_SHIFT 0 /**< Shift value for ADC_DATA */
-#define _ADC_SINGLEDATA_DATA_MASK 0xFFFFFFFFUL /**< Bit mask for ADC_DATA */
-#define _ADC_SINGLEDATA_DATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLEDATA */
-#define ADC_SINGLEDATA_DATA_DEFAULT (_ADC_SINGLEDATA_DATA_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_SINGLEDATA */
-
-/* Bit fields for ADC SCANDATA */
-#define _ADC_SCANDATA_RESETVALUE 0x00000000UL /**< Default value for ADC_SCANDATA */
-#define _ADC_SCANDATA_MASK 0xFFFFFFFFUL /**< Mask for ADC_SCANDATA */
-#define _ADC_SCANDATA_DATA_SHIFT 0 /**< Shift value for ADC_DATA */
-#define _ADC_SCANDATA_DATA_MASK 0xFFFFFFFFUL /**< Bit mask for ADC_DATA */
-#define _ADC_SCANDATA_DATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANDATA */
-#define ADC_SCANDATA_DATA_DEFAULT (_ADC_SCANDATA_DATA_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_SCANDATA */
-
-/* Bit fields for ADC SINGLEDATAP */
-#define _ADC_SINGLEDATAP_RESETVALUE 0x00000000UL /**< Default value for ADC_SINGLEDATAP */
-#define _ADC_SINGLEDATAP_MASK 0xFFFFFFFFUL /**< Mask for ADC_SINGLEDATAP */
-#define _ADC_SINGLEDATAP_DATAP_SHIFT 0 /**< Shift value for ADC_DATAP */
-#define _ADC_SINGLEDATAP_DATAP_MASK 0xFFFFFFFFUL /**< Bit mask for ADC_DATAP */
-#define _ADC_SINGLEDATAP_DATAP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SINGLEDATAP */
-#define ADC_SINGLEDATAP_DATAP_DEFAULT (_ADC_SINGLEDATAP_DATAP_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_SINGLEDATAP */
-
-/* Bit fields for ADC SCANDATAP */
-#define _ADC_SCANDATAP_RESETVALUE 0x00000000UL /**< Default value for ADC_SCANDATAP */
-#define _ADC_SCANDATAP_MASK 0xFFFFFFFFUL /**< Mask for ADC_SCANDATAP */
-#define _ADC_SCANDATAP_DATAP_SHIFT 0 /**< Shift value for ADC_DATAP */
-#define _ADC_SCANDATAP_DATAP_MASK 0xFFFFFFFFUL /**< Bit mask for ADC_DATAP */
-#define _ADC_SCANDATAP_DATAP_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_SCANDATAP */
-#define ADC_SCANDATAP_DATAP_DEFAULT (_ADC_SCANDATAP_DATAP_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_SCANDATAP */
-
-/* Bit fields for ADC CAL */
-#define _ADC_CAL_RESETVALUE 0x3F003F00UL /**< Default value for ADC_CAL */
-#define _ADC_CAL_MASK 0x7F7F7F7FUL /**< Mask for ADC_CAL */
-#define _ADC_CAL_SINGLEOFFSET_SHIFT 0 /**< Shift value for ADC_SINGLEOFFSET */
-#define _ADC_CAL_SINGLEOFFSET_MASK 0x7FUL /**< Bit mask for ADC_SINGLEOFFSET */
-#define _ADC_CAL_SINGLEOFFSET_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CAL */
-#define ADC_CAL_SINGLEOFFSET_DEFAULT (_ADC_CAL_SINGLEOFFSET_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_CAL */
-#define _ADC_CAL_SINGLEGAIN_SHIFT 8 /**< Shift value for ADC_SINGLEGAIN */
-#define _ADC_CAL_SINGLEGAIN_MASK 0x7F00UL /**< Bit mask for ADC_SINGLEGAIN */
-#define _ADC_CAL_SINGLEGAIN_DEFAULT 0x0000003FUL /**< Mode DEFAULT for ADC_CAL */
-#define ADC_CAL_SINGLEGAIN_DEFAULT (_ADC_CAL_SINGLEGAIN_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_CAL */
-#define _ADC_CAL_SCANOFFSET_SHIFT 16 /**< Shift value for ADC_SCANOFFSET */
-#define _ADC_CAL_SCANOFFSET_MASK 0x7F0000UL /**< Bit mask for ADC_SCANOFFSET */
-#define _ADC_CAL_SCANOFFSET_DEFAULT 0x00000000UL /**< Mode DEFAULT for ADC_CAL */
-#define ADC_CAL_SCANOFFSET_DEFAULT (_ADC_CAL_SCANOFFSET_DEFAULT << 16) /**< Shifted mode DEFAULT for ADC_CAL */
-#define _ADC_CAL_SCANGAIN_SHIFT 24 /**< Shift value for ADC_SCANGAIN */
-#define _ADC_CAL_SCANGAIN_MASK 0x7F000000UL /**< Bit mask for ADC_SCANGAIN */
-#define _ADC_CAL_SCANGAIN_DEFAULT 0x0000003FUL /**< Mode DEFAULT for ADC_CAL */
-#define ADC_CAL_SCANGAIN_DEFAULT (_ADC_CAL_SCANGAIN_DEFAULT << 24) /**< Shifted mode DEFAULT for ADC_CAL */
-
-/* Bit fields for ADC BIASPROG */
-#define _ADC_BIASPROG_RESETVALUE 0x00000747UL /**< Default value for ADC_BIASPROG */
-#define _ADC_BIASPROG_MASK 0x00000F4FUL /**< Mask for ADC_BIASPROG */
-#define _ADC_BIASPROG_BIASPROG_SHIFT 0 /**< Shift value for ADC_BIASPROG */
-#define _ADC_BIASPROG_BIASPROG_MASK 0xFUL /**< Bit mask for ADC_BIASPROG */
-#define _ADC_BIASPROG_BIASPROG_DEFAULT 0x00000007UL /**< Mode DEFAULT for ADC_BIASPROG */
-#define ADC_BIASPROG_BIASPROG_DEFAULT (_ADC_BIASPROG_BIASPROG_DEFAULT << 0) /**< Shifted mode DEFAULT for ADC_BIASPROG */
-#define ADC_BIASPROG_HALFBIAS (0x1UL << 6) /**< Half Bias Current */
-#define _ADC_BIASPROG_HALFBIAS_SHIFT 6 /**< Shift value for ADC_HALFBIAS */
-#define _ADC_BIASPROG_HALFBIAS_MASK 0x40UL /**< Bit mask for ADC_HALFBIAS */
-#define _ADC_BIASPROG_HALFBIAS_DEFAULT 0x00000001UL /**< Mode DEFAULT for ADC_BIASPROG */
-#define ADC_BIASPROG_HALFBIAS_DEFAULT (_ADC_BIASPROG_HALFBIAS_DEFAULT << 6) /**< Shifted mode DEFAULT for ADC_BIASPROG */
-#define _ADC_BIASPROG_COMPBIAS_SHIFT 8 /**< Shift value for ADC_COMPBIAS */
-#define _ADC_BIASPROG_COMPBIAS_MASK 0xF00UL /**< Bit mask for ADC_COMPBIAS */
-#define _ADC_BIASPROG_COMPBIAS_DEFAULT 0x00000007UL /**< Mode DEFAULT for ADC_BIASPROG */
-#define ADC_BIASPROG_COMPBIAS_DEFAULT (_ADC_BIASPROG_COMPBIAS_DEFAULT << 8) /**< Shifted mode DEFAULT for ADC_BIASPROG */
-
-/** @} End of group EFM32ZG_ADC */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_aes.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_aes.h
deleted file mode 100644
index 6ddd39a78e..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_aes.h
+++ /dev/null
@@ -1,200 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_AES register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_AES
- * @{
- * @brief EFM32ZG_AES Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t DATA; /**< DATA Register */
- __IOM uint32_t XORDATA; /**< XORDATA Register */
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t KEYLA; /**< KEY Low Register */
- __IOM uint32_t KEYLB; /**< KEY Low Register */
- __IOM uint32_t KEYLC; /**< KEY Low Register */
- __IOM uint32_t KEYLD; /**< KEY Low Register */
-} AES_TypeDef; /** AES Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_AES_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for AES CTRL */
-#define _AES_CTRL_RESETVALUE 0x00000000UL /**< Default value for AES_CTRL */
-#define _AES_CTRL_MASK 0x00000071UL /**< Mask for AES_CTRL */
-#define AES_CTRL_DECRYPT (0x1UL << 0) /**< Decryption/Encryption Mode */
-#define _AES_CTRL_DECRYPT_SHIFT 0 /**< Shift value for AES_DECRYPT */
-#define _AES_CTRL_DECRYPT_MASK 0x1UL /**< Bit mask for AES_DECRYPT */
-#define _AES_CTRL_DECRYPT_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_CTRL */
-#define AES_CTRL_DECRYPT_DEFAULT (_AES_CTRL_DECRYPT_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_CTRL */
-#define AES_CTRL_DATASTART (0x1UL << 4) /**< AES_DATA Write Start */
-#define _AES_CTRL_DATASTART_SHIFT 4 /**< Shift value for AES_DATASTART */
-#define _AES_CTRL_DATASTART_MASK 0x10UL /**< Bit mask for AES_DATASTART */
-#define _AES_CTRL_DATASTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_CTRL */
-#define AES_CTRL_DATASTART_DEFAULT (_AES_CTRL_DATASTART_DEFAULT << 4) /**< Shifted mode DEFAULT for AES_CTRL */
-#define AES_CTRL_XORSTART (0x1UL << 5) /**< AES_XORDATA Write Start */
-#define _AES_CTRL_XORSTART_SHIFT 5 /**< Shift value for AES_XORSTART */
-#define _AES_CTRL_XORSTART_MASK 0x20UL /**< Bit mask for AES_XORSTART */
-#define _AES_CTRL_XORSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_CTRL */
-#define AES_CTRL_XORSTART_DEFAULT (_AES_CTRL_XORSTART_DEFAULT << 5) /**< Shifted mode DEFAULT for AES_CTRL */
-#define AES_CTRL_BYTEORDER (0x1UL << 6) /**< Configure byte order in data and key registers */
-#define _AES_CTRL_BYTEORDER_SHIFT 6 /**< Shift value for AES_BYTEORDER */
-#define _AES_CTRL_BYTEORDER_MASK 0x40UL /**< Bit mask for AES_BYTEORDER */
-#define _AES_CTRL_BYTEORDER_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_CTRL */
-#define AES_CTRL_BYTEORDER_DEFAULT (_AES_CTRL_BYTEORDER_DEFAULT << 6) /**< Shifted mode DEFAULT for AES_CTRL */
-
-/* Bit fields for AES CMD */
-#define _AES_CMD_RESETVALUE 0x00000000UL /**< Default value for AES_CMD */
-#define _AES_CMD_MASK 0x00000003UL /**< Mask for AES_CMD */
-#define AES_CMD_START (0x1UL << 0) /**< Encryption/Decryption Start */
-#define _AES_CMD_START_SHIFT 0 /**< Shift value for AES_START */
-#define _AES_CMD_START_MASK 0x1UL /**< Bit mask for AES_START */
-#define _AES_CMD_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_CMD */
-#define AES_CMD_START_DEFAULT (_AES_CMD_START_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_CMD */
-#define AES_CMD_STOP (0x1UL << 1) /**< Encryption/Decryption Stop */
-#define _AES_CMD_STOP_SHIFT 1 /**< Shift value for AES_STOP */
-#define _AES_CMD_STOP_MASK 0x2UL /**< Bit mask for AES_STOP */
-#define _AES_CMD_STOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_CMD */
-#define AES_CMD_STOP_DEFAULT (_AES_CMD_STOP_DEFAULT << 1) /**< Shifted mode DEFAULT for AES_CMD */
-
-/* Bit fields for AES STATUS */
-#define _AES_STATUS_RESETVALUE 0x00000000UL /**< Default value for AES_STATUS */
-#define _AES_STATUS_MASK 0x00000001UL /**< Mask for AES_STATUS */
-#define AES_STATUS_RUNNING (0x1UL << 0) /**< AES Running */
-#define _AES_STATUS_RUNNING_SHIFT 0 /**< Shift value for AES_RUNNING */
-#define _AES_STATUS_RUNNING_MASK 0x1UL /**< Bit mask for AES_RUNNING */
-#define _AES_STATUS_RUNNING_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_STATUS */
-#define AES_STATUS_RUNNING_DEFAULT (_AES_STATUS_RUNNING_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_STATUS */
-
-/* Bit fields for AES IEN */
-#define _AES_IEN_RESETVALUE 0x00000000UL /**< Default value for AES_IEN */
-#define _AES_IEN_MASK 0x00000001UL /**< Mask for AES_IEN */
-#define AES_IEN_DONE (0x1UL << 0) /**< Encryption/Decryption Done Interrupt Enable */
-#define _AES_IEN_DONE_SHIFT 0 /**< Shift value for AES_DONE */
-#define _AES_IEN_DONE_MASK 0x1UL /**< Bit mask for AES_DONE */
-#define _AES_IEN_DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_IEN */
-#define AES_IEN_DONE_DEFAULT (_AES_IEN_DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_IEN */
-
-/* Bit fields for AES IF */
-#define _AES_IF_RESETVALUE 0x00000000UL /**< Default value for AES_IF */
-#define _AES_IF_MASK 0x00000001UL /**< Mask for AES_IF */
-#define AES_IF_DONE (0x1UL << 0) /**< Encryption/Decryption Done Interrupt Flag */
-#define _AES_IF_DONE_SHIFT 0 /**< Shift value for AES_DONE */
-#define _AES_IF_DONE_MASK 0x1UL /**< Bit mask for AES_DONE */
-#define _AES_IF_DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_IF */
-#define AES_IF_DONE_DEFAULT (_AES_IF_DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_IF */
-
-/* Bit fields for AES IFS */
-#define _AES_IFS_RESETVALUE 0x00000000UL /**< Default value for AES_IFS */
-#define _AES_IFS_MASK 0x00000001UL /**< Mask for AES_IFS */
-#define AES_IFS_DONE (0x1UL << 0) /**< Encryption/Decryption Done Interrupt Flag Set */
-#define _AES_IFS_DONE_SHIFT 0 /**< Shift value for AES_DONE */
-#define _AES_IFS_DONE_MASK 0x1UL /**< Bit mask for AES_DONE */
-#define _AES_IFS_DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_IFS */
-#define AES_IFS_DONE_DEFAULT (_AES_IFS_DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_IFS */
-
-/* Bit fields for AES IFC */
-#define _AES_IFC_RESETVALUE 0x00000000UL /**< Default value for AES_IFC */
-#define _AES_IFC_MASK 0x00000001UL /**< Mask for AES_IFC */
-#define AES_IFC_DONE (0x1UL << 0) /**< Encryption/Decryption Done Interrupt Flag Clear */
-#define _AES_IFC_DONE_SHIFT 0 /**< Shift value for AES_DONE */
-#define _AES_IFC_DONE_MASK 0x1UL /**< Bit mask for AES_DONE */
-#define _AES_IFC_DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_IFC */
-#define AES_IFC_DONE_DEFAULT (_AES_IFC_DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_IFC */
-
-/* Bit fields for AES DATA */
-#define _AES_DATA_RESETVALUE 0x00000000UL /**< Default value for AES_DATA */
-#define _AES_DATA_MASK 0xFFFFFFFFUL /**< Mask for AES_DATA */
-#define _AES_DATA_DATA_SHIFT 0 /**< Shift value for AES_DATA */
-#define _AES_DATA_DATA_MASK 0xFFFFFFFFUL /**< Bit mask for AES_DATA */
-#define _AES_DATA_DATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_DATA */
-#define AES_DATA_DATA_DEFAULT (_AES_DATA_DATA_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_DATA */
-
-/* Bit fields for AES XORDATA */
-#define _AES_XORDATA_RESETVALUE 0x00000000UL /**< Default value for AES_XORDATA */
-#define _AES_XORDATA_MASK 0xFFFFFFFFUL /**< Mask for AES_XORDATA */
-#define _AES_XORDATA_XORDATA_SHIFT 0 /**< Shift value for AES_XORDATA */
-#define _AES_XORDATA_XORDATA_MASK 0xFFFFFFFFUL /**< Bit mask for AES_XORDATA */
-#define _AES_XORDATA_XORDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_XORDATA */
-#define AES_XORDATA_XORDATA_DEFAULT (_AES_XORDATA_XORDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_XORDATA */
-
-/* Bit fields for AES KEYLA */
-#define _AES_KEYLA_RESETVALUE 0x00000000UL /**< Default value for AES_KEYLA */
-#define _AES_KEYLA_MASK 0xFFFFFFFFUL /**< Mask for AES_KEYLA */
-#define _AES_KEYLA_KEYLA_SHIFT 0 /**< Shift value for AES_KEYLA */
-#define _AES_KEYLA_KEYLA_MASK 0xFFFFFFFFUL /**< Bit mask for AES_KEYLA */
-#define _AES_KEYLA_KEYLA_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_KEYLA */
-#define AES_KEYLA_KEYLA_DEFAULT (_AES_KEYLA_KEYLA_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_KEYLA */
-
-/* Bit fields for AES KEYLB */
-#define _AES_KEYLB_RESETVALUE 0x00000000UL /**< Default value for AES_KEYLB */
-#define _AES_KEYLB_MASK 0xFFFFFFFFUL /**< Mask for AES_KEYLB */
-#define _AES_KEYLB_KEYLB_SHIFT 0 /**< Shift value for AES_KEYLB */
-#define _AES_KEYLB_KEYLB_MASK 0xFFFFFFFFUL /**< Bit mask for AES_KEYLB */
-#define _AES_KEYLB_KEYLB_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_KEYLB */
-#define AES_KEYLB_KEYLB_DEFAULT (_AES_KEYLB_KEYLB_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_KEYLB */
-
-/* Bit fields for AES KEYLC */
-#define _AES_KEYLC_RESETVALUE 0x00000000UL /**< Default value for AES_KEYLC */
-#define _AES_KEYLC_MASK 0xFFFFFFFFUL /**< Mask for AES_KEYLC */
-#define _AES_KEYLC_KEYLC_SHIFT 0 /**< Shift value for AES_KEYLC */
-#define _AES_KEYLC_KEYLC_MASK 0xFFFFFFFFUL /**< Bit mask for AES_KEYLC */
-#define _AES_KEYLC_KEYLC_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_KEYLC */
-#define AES_KEYLC_KEYLC_DEFAULT (_AES_KEYLC_KEYLC_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_KEYLC */
-
-/* Bit fields for AES KEYLD */
-#define _AES_KEYLD_RESETVALUE 0x00000000UL /**< Default value for AES_KEYLD */
-#define _AES_KEYLD_MASK 0xFFFFFFFFUL /**< Mask for AES_KEYLD */
-#define _AES_KEYLD_KEYLD_SHIFT 0 /**< Shift value for AES_KEYLD */
-#define _AES_KEYLD_KEYLD_MASK 0xFFFFFFFFUL /**< Bit mask for AES_KEYLD */
-#define _AES_KEYLD_KEYLD_DEFAULT 0x00000000UL /**< Mode DEFAULT for AES_KEYLD */
-#define AES_KEYLD_KEYLD_DEFAULT (_AES_KEYLD_KEYLD_DEFAULT << 0) /**< Shifted mode DEFAULT for AES_KEYLD */
-
-/** @} End of group EFM32ZG_AES */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_af_pins.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_af_pins.h
deleted file mode 100644
index 5625e06052..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_af_pins.h
+++ /dev/null
@@ -1,79 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_AF_PINS register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_AF_Pins
- * @{
- ******************************************************************************/
-
-#define AF_CMU_CLK0_PIN(i) ((i) == 0 ? 2 : (i) == 1 ? -1 : (i) == 2 ? 7 : -1) /**< Pin number for AF_CMU_CLK0 location number i */
-#define AF_CMU_CLK1_PIN(i) ((i) == 0 ? 1 : (i) == 1 ? -1 : (i) == 2 ? 12 : -1) /**< Pin number for AF_CMU_CLK1 location number i */
-#define AF_TIMER0_CC0_PIN(i) ((i) == 0 ? 0 : (i) == 1 ? 0 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 0 : (i) == 5 ? 0 : -1) /**< Pin number for AF_TIMER0_CC0 location number i */
-#define AF_TIMER0_CC1_PIN(i) ((i) == 0 ? 1 : (i) == 1 ? 1 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 0 : (i) == 5 ? 1 : -1) /**< Pin number for AF_TIMER0_CC1 location number i */
-#define AF_TIMER0_CC2_PIN(i) ((i) == 0 ? 2 : (i) == 1 ? 2 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 1 : (i) == 5 ? 2 : -1) /**< Pin number for AF_TIMER0_CC2 location number i */
-#define AF_TIMER0_CDTI0_PIN(i) (-1) /**< Pin number for AF_TIMER0_CDTI0 location number i */
-#define AF_TIMER0_CDTI1_PIN(i) (-1) /**< Pin number for AF_TIMER0_CDTI1 location number i */
-#define AF_TIMER0_CDTI2_PIN(i) (-1) /**< Pin number for AF_TIMER0_CDTI2 location number i */
-#define AF_TIMER1_CC0_PIN(i) ((i) == 0 ? 13 : (i) == 1 ? 10 : (i) == 2 ? -1 : (i) == 3 ? 7 : (i) == 4 ? 6 : -1) /**< Pin number for AF_TIMER1_CC0 location number i */
-#define AF_TIMER1_CC1_PIN(i) ((i) == 0 ? 14 : (i) == 1 ? 11 : (i) == 2 ? -1 : (i) == 3 ? 8 : (i) == 4 ? 7 : -1) /**< Pin number for AF_TIMER1_CC1 location number i */
-#define AF_TIMER1_CC2_PIN(i) ((i) == 0 ? 15 : (i) == 1 ? 12 : (i) == 2 ? -1 : (i) == 3 ? 11 : (i) == 4 ? 13 : -1) /**< Pin number for AF_TIMER1_CC2 location number i */
-#define AF_TIMER1_CDTI0_PIN(i) (-1) /**< Pin number for AF_TIMER1_CDTI0 location number i */
-#define AF_TIMER1_CDTI1_PIN(i) (-1) /**< Pin number for AF_TIMER1_CDTI1 location number i */
-#define AF_TIMER1_CDTI2_PIN(i) (-1) /**< Pin number for AF_TIMER1_CDTI2 location number i */
-#define AF_ACMP0_OUT_PIN(i) ((i) == 0 ? 13 : (i) == 1 ? -1 : (i) == 2 ? 6 : -1) /**< Pin number for AF_ACMP0_OUT location number i */
-#define AF_USART1_TX_PIN(i) ((i) == 0 ? 0 : (i) == 1 ? -1 : (i) == 2 ? 7 : (i) == 3 ? 7 : -1) /**< Pin number for AF_USART1_TX location number i */
-#define AF_USART1_RX_PIN(i) ((i) == 0 ? 1 : (i) == 1 ? -1 : (i) == 2 ? 6 : (i) == 3 ? 6 : -1) /**< Pin number for AF_USART1_RX location number i */
-#define AF_USART1_CLK_PIN(i) ((i) == 0 ? 7 : (i) == 1 ? -1 : (i) == 2 ? 0 : (i) == 3 ? 15 : -1) /**< Pin number for AF_USART1_CLK location number i */
-#define AF_USART1_CS_PIN(i) ((i) == 0 ? 8 : (i) == 1 ? -1 : (i) == 2 ? 1 : (i) == 3 ? 14 : -1) /**< Pin number for AF_USART1_CS location number i */
-#define AF_PRS_CH0_PIN(i) ((i) == 0 ? 0 : (i) == 1 ? 3 : (i) == 2 ? 14 : -1) /**< Pin number for AF_PRS_CH0 location number i */
-#define AF_PRS_CH1_PIN(i) ((i) == 0 ? 1 : (i) == 1 ? 4 : (i) == 2 ? 15 : -1) /**< Pin number for AF_PRS_CH1 location number i */
-#define AF_PRS_CH2_PIN(i) ((i) == 0 ? 0 : (i) == 1 ? 5 : (i) == 2 ? 10 : -1) /**< Pin number for AF_PRS_CH2 location number i */
-#define AF_PRS_CH3_PIN(i) ((i) == 0 ? 1 : (i) == 1 ? -1 : (i) == 2 ? 11 : -1) /**< Pin number for AF_PRS_CH3 location number i */
-#define AF_LEUART0_TX_PIN(i) ((i) == 0 ? 4 : (i) == 1 ? 13 : (i) == 2 ? -1 : (i) == 3 ? 0 : (i) == 4 ? 2 : -1) /**< Pin number for AF_LEUART0_TX location number i */
-#define AF_LEUART0_RX_PIN(i) ((i) == 0 ? 5 : (i) == 1 ? 14 : (i) == 2 ? -1 : (i) == 3 ? 1 : (i) == 4 ? 0 : -1) /**< Pin number for AF_LEUART0_RX location number i */
-#define AF_PCNT0_S0IN_PIN(i) ((i) == 0 ? 13 : (i) == 1 ? -1 : (i) == 2 ? 0 : (i) == 3 ? 6 : -1) /**< Pin number for AF_PCNT0_S0IN location number i */
-#define AF_PCNT0_S1IN_PIN(i) ((i) == 0 ? 14 : (i) == 1 ? -1 : (i) == 2 ? 1 : (i) == 3 ? 7 : -1) /**< Pin number for AF_PCNT0_S1IN location number i */
-#define AF_I2C0_SDA_PIN(i) ((i) == 0 ? 0 : (i) == 1 ? 6 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 0 : (i) == 5 ? 0 : (i) == 6 ? 12 : -1) /**< Pin number for AF_I2C0_SDA location number i */
-#define AF_I2C0_SCL_PIN(i) ((i) == 0 ? 1 : (i) == 1 ? 7 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 1 : (i) == 5 ? 1 : (i) == 6 ? 13 : -1) /**< Pin number for AF_I2C0_SCL location number i */
-#define AF_DBG_SWDIO_PIN(i) ((i) == 0 ? 1 : -1) /**< Pin number for AF_DBG_SWDIO location number i */
-#define AF_DBG_SWCLK_PIN(i) ((i) == 0 ? 0 : -1) /**< Pin number for AF_DBG_SWCLK location number i */
-
-/** @} End of group EFM32ZG_AF_Pins */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_af_ports.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_af_ports.h
deleted file mode 100644
index 4399e63cb8..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_af_ports.h
+++ /dev/null
@@ -1,79 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_AF_PORTS register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_AF_Ports
- * @{
- ******************************************************************************/
-
-#define AF_CMU_CLK0_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? -1 : (i) == 2 ? 3 : -1) /**< Port number for AF_CMU_CLK0 location number i */
-#define AF_CMU_CLK1_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? -1 : (i) == 2 ? 4 : -1) /**< Port number for AF_CMU_CLK1 location number i */
-#define AF_TIMER0_CC0_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 0 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 0 : (i) == 5 ? 5 : -1) /**< Port number for AF_TIMER0_CC0 location number i */
-#define AF_TIMER0_CC1_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 0 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 2 : (i) == 5 ? 5 : -1) /**< Port number for AF_TIMER0_CC1 location number i */
-#define AF_TIMER0_CC2_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 0 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 2 : (i) == 5 ? 5 : -1) /**< Port number for AF_TIMER0_CC2 location number i */
-#define AF_TIMER0_CDTI0_PORT(i) (-1) /**< Port number for AF_TIMER0_CDTI0 location number i */
-#define AF_TIMER0_CDTI1_PORT(i) (-1) /**< Port number for AF_TIMER0_CDTI1 location number i */
-#define AF_TIMER0_CDTI2_PORT(i) (-1) /**< Port number for AF_TIMER0_CDTI2 location number i */
-#define AF_TIMER1_CC0_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? 4 : (i) == 2 ? -1 : (i) == 3 ? 1 : (i) == 4 ? 3 : -1) /**< Port number for AF_TIMER1_CC0 location number i */
-#define AF_TIMER1_CC1_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? 4 : (i) == 2 ? -1 : (i) == 3 ? 1 : (i) == 4 ? 3 : -1) /**< Port number for AF_TIMER1_CC1 location number i */
-#define AF_TIMER1_CC2_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? 4 : (i) == 2 ? -1 : (i) == 3 ? 1 : (i) == 4 ? 2 : -1) /**< Port number for AF_TIMER1_CC2 location number i */
-#define AF_TIMER1_CDTI0_PORT(i) (-1) /**< Port number for AF_TIMER1_CDTI0 location number i */
-#define AF_TIMER1_CDTI1_PORT(i) (-1) /**< Port number for AF_TIMER1_CDTI1 location number i */
-#define AF_TIMER1_CDTI2_PORT(i) (-1) /**< Port number for AF_TIMER1_CDTI2 location number i */
-#define AF_ACMP0_OUT_PORT(i) ((i) == 0 ? 4 : (i) == 1 ? -1 : (i) == 2 ? 3 : -1) /**< Port number for AF_ACMP0_OUT location number i */
-#define AF_USART1_TX_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? -1 : (i) == 2 ? 3 : (i) == 3 ? 3 : -1) /**< Port number for AF_USART1_TX location number i */
-#define AF_USART1_RX_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? -1 : (i) == 2 ? 3 : (i) == 3 ? 3 : -1) /**< Port number for AF_USART1_RX location number i */
-#define AF_USART1_CLK_PORT(i) ((i) == 0 ? 1 : (i) == 1 ? -1 : (i) == 2 ? 5 : (i) == 3 ? 2 : -1) /**< Port number for AF_USART1_CLK location number i */
-#define AF_USART1_CS_PORT(i) ((i) == 0 ? 1 : (i) == 1 ? -1 : (i) == 2 ? 5 : (i) == 3 ? 2 : -1) /**< Port number for AF_USART1_CS location number i */
-#define AF_PRS_CH0_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 5 : (i) == 2 ? 2 : -1) /**< Port number for AF_PRS_CH0 location number i */
-#define AF_PRS_CH1_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 5 : (i) == 2 ? 2 : -1) /**< Port number for AF_PRS_CH1 location number i */
-#define AF_PRS_CH2_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? 5 : (i) == 2 ? 4 : -1) /**< Port number for AF_PRS_CH2 location number i */
-#define AF_PRS_CH3_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? -1 : (i) == 2 ? 4 : -1) /**< Port number for AF_PRS_CH3 location number i */
-#define AF_LEUART0_TX_PORT(i) ((i) == 0 ? 3 : (i) == 1 ? 1 : (i) == 2 ? -1 : (i) == 3 ? 5 : (i) == 4 ? 5 : -1) /**< Port number for AF_LEUART0_TX location number i */
-#define AF_LEUART0_RX_PORT(i) ((i) == 0 ? 3 : (i) == 1 ? 1 : (i) == 2 ? -1 : (i) == 3 ? 5 : (i) == 4 ? 0 : -1) /**< Port number for AF_LEUART0_RX location number i */
-#define AF_PCNT0_S0IN_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? -1 : (i) == 2 ? 2 : (i) == 3 ? 3 : -1) /**< Port number for AF_PCNT0_S0IN location number i */
-#define AF_PCNT0_S1IN_PORT(i) ((i) == 0 ? 2 : (i) == 1 ? -1 : (i) == 2 ? 2 : (i) == 3 ? 3 : -1) /**< Port number for AF_PCNT0_S1IN location number i */
-#define AF_I2C0_SDA_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 3 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 2 : (i) == 5 ? 5 : (i) == 6 ? 4 : -1) /**< Port number for AF_I2C0_SDA location number i */
-#define AF_I2C0_SCL_PORT(i) ((i) == 0 ? 0 : (i) == 1 ? 3 : (i) == 2 ? -1 : (i) == 3 ? -1 : (i) == 4 ? 2 : (i) == 5 ? 5 : (i) == 6 ? 4 : -1) /**< Port number for AF_I2C0_SCL location number i */
-#define AF_DBG_SWDIO_PORT(i) ((i) == 0 ? 5 : -1) /**< Port number for AF_DBG_SWDIO location number i */
-#define AF_DBG_SWCLK_PORT(i) ((i) == 0 ? 5 : -1) /**< Port number for AF_DBG_SWCLK location number i */
-
-/** @} End of group EFM32ZG_AF_Ports */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_calibrate.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_calibrate.h
deleted file mode 100644
index ef4ab49051..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_calibrate.h
+++ /dev/null
@@ -1,52 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_CALIBRATE register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_CALIBRATE
- * @{
- ******************************************************************************/
-#define CALIBRATE_MAX_REGISTERS 50 /**< Max number of address/value pairs for calibration */
-
-typedef struct {
- __IM uint32_t ADDRESS; /**< Address of calibration register */
- __IM uint32_t VALUE; /**< Default value for calibration register */
-} CALIBRATE_TypeDef; /** @} */
-
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_cmu.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_cmu.h
deleted file mode 100644
index 4de8031111..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_cmu.h
+++ /dev/null
@@ -1,985 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_CMU register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_CMU
- * @{
- * @brief EFM32ZG_CMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< CMU Control Register */
- __IOM uint32_t HFCORECLKDIV; /**< High Frequency Core Clock Division Register */
- __IOM uint32_t HFPERCLKDIV; /**< High Frequency Peripheral Clock Division Register */
- __IOM uint32_t HFRCOCTRL; /**< HFRCO Control Register */
- __IOM uint32_t LFRCOCTRL; /**< LFRCO Control Register */
- __IOM uint32_t AUXHFRCOCTRL; /**< AUXHFRCO Control Register */
- __IOM uint32_t CALCTRL; /**< Calibration Control Register */
- __IOM uint32_t CALCNT; /**< Calibration Counter Register */
- __IOM uint32_t OSCENCMD; /**< Oscillator Enable/Disable Command Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IOM uint32_t LFCLKSEL; /**< Low Frequency Clock Select Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t HFCORECLKEN0; /**< High Frequency Core Clock Enable Register 0 */
- __IOM uint32_t HFPERCLKEN0; /**< High Frequency Peripheral Clock Enable Register 0 */
- uint32_t RESERVED0[2U]; /**< Reserved for future use **/
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IOM uint32_t LFACLKEN0; /**< Low Frequency A Clock Enable Register 0 (Async Reg) */
- uint32_t RESERVED1[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBCLKEN0; /**< Low Frequency B Clock Enable Register 0 (Async Reg) */
-
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFAPRESC0; /**< Low Frequency A Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED3[1U]; /**< Reserved for future use **/
- __IOM uint32_t LFBPRESC0; /**< Low Frequency B Prescaler Register 0 (Async Reg) */
- uint32_t RESERVED4[1U]; /**< Reserved for future use **/
- __IOM uint32_t PCNTCTRL; /**< PCNT Control Register */
-
- uint32_t RESERVED5[1U]; /**< Reserved for future use **/
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
-} CMU_TypeDef; /** CMU Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_CMU_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for CMU CTRL */
-#define _CMU_CTRL_RESETVALUE 0x000C262CUL /**< Default value for CMU_CTRL */
-#define _CMU_CTRL_MASK 0x07FE3EEFUL /**< Mask for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_SHIFT 0 /**< Shift value for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_MASK 0x3UL /**< Bit mask for CMU_HFXOMODE */
-#define _CMU_CTRL_HFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DEFAULT (_CMU_CTRL_HFXOMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_XTAL (_CMU_CTRL_HFXOMODE_XTAL << 0) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_BUFEXTCLK (_CMU_CTRL_HFXOMODE_BUFEXTCLK << 0) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_HFXOMODE_DIGEXTCLK (_CMU_CTRL_HFXOMODE_DIGEXTCLK << 0) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_SHIFT 2 /**< Shift value for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_MASK 0xCUL /**< Bit mask for CMU_HFXOBOOST */
-#define _CMU_CTRL_HFXOBOOST_50PCENT 0x00000000UL /**< Mode 50PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_70PCENT 0x00000001UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_80PCENT 0x00000002UL /**< Mode 80PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBOOST_100PCENT 0x00000003UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_50PCENT (_CMU_CTRL_HFXOBOOST_50PCENT << 2) /**< Shifted mode 50PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_70PCENT (_CMU_CTRL_HFXOBOOST_70PCENT << 2) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_80PCENT (_CMU_CTRL_HFXOBOOST_80PCENT << 2) /**< Shifted mode 80PCENT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_DEFAULT (_CMU_CTRL_HFXOBOOST_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBOOST_100PCENT (_CMU_CTRL_HFXOBOOST_100PCENT << 2) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define _CMU_CTRL_HFXOBUFCUR_SHIFT 5 /**< Shift value for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_MASK 0x60UL /**< Bit mask for CMU_HFXOBUFCUR */
-#define _CMU_CTRL_HFXOBUFCUR_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOBUFCUR_DEFAULT (_CMU_CTRL_HFXOBUFCUR_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN (0x1UL << 7) /**< HFXO Glitch Detector Enable */
-#define _CMU_CTRL_HFXOGLITCHDETEN_SHIFT 7 /**< Shift value for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_MASK 0x80UL /**< Bit mask for CMU_HFXOGLITCHDETEN */
-#define _CMU_CTRL_HFXOGLITCHDETEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOGLITCHDETEN_DEFAULT (_CMU_CTRL_HFXOGLITCHDETEN_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_SHIFT 9 /**< Shift value for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_MASK 0x600UL /**< Bit mask for CMU_HFXOTIMEOUT */
-#define _CMU_CTRL_HFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_256CYCLES 0x00000001UL /**< Mode 256CYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_1KCYCLES 0x00000002UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_HFXOTIMEOUT_16KCYCLES 0x00000003UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_8CYCLES (_CMU_CTRL_HFXOTIMEOUT_8CYCLES << 9) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_256CYCLES (_CMU_CTRL_HFXOTIMEOUT_256CYCLES << 9) /**< Shifted mode 256CYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_1KCYCLES (_CMU_CTRL_HFXOTIMEOUT_1KCYCLES << 9) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_DEFAULT (_CMU_CTRL_HFXOTIMEOUT_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_HFXOTIMEOUT_16KCYCLES (_CMU_CTRL_HFXOTIMEOUT_16KCYCLES << 9) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_SHIFT 11 /**< Shift value for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_MASK 0x1800UL /**< Bit mask for CMU_LFXOMODE */
-#define _CMU_CTRL_LFXOMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_XTAL 0x00000000UL /**< Mode XTAL for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_BUFEXTCLK 0x00000001UL /**< Mode BUFEXTCLK for CMU_CTRL */
-#define _CMU_CTRL_LFXOMODE_DIGEXTCLK 0x00000002UL /**< Mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DEFAULT (_CMU_CTRL_LFXOMODE_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_XTAL (_CMU_CTRL_LFXOMODE_XTAL << 11) /**< Shifted mode XTAL for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_BUFEXTCLK (_CMU_CTRL_LFXOMODE_BUFEXTCLK << 11) /**< Shifted mode BUFEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOMODE_DIGEXTCLK (_CMU_CTRL_LFXOMODE_DIGEXTCLK << 11) /**< Shifted mode DIGEXTCLK for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST (0x1UL << 13) /**< LFXO Start-up Boost Current */
-#define _CMU_CTRL_LFXOBOOST_SHIFT 13 /**< Shift value for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_MASK 0x2000UL /**< Bit mask for CMU_LFXOBOOST */
-#define _CMU_CTRL_LFXOBOOST_70PCENT 0x00000000UL /**< Mode 70PCENT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOBOOST_100PCENT 0x00000001UL /**< Mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_70PCENT (_CMU_CTRL_LFXOBOOST_70PCENT << 13) /**< Shifted mode 70PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_DEFAULT (_CMU_CTRL_LFXOBOOST_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBOOST_100PCENT (_CMU_CTRL_LFXOBOOST_100PCENT << 13) /**< Shifted mode 100PCENT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR (0x1UL << 17) /**< LFXO Boost Buffer Current */
-#define _CMU_CTRL_LFXOBUFCUR_SHIFT 17 /**< Shift value for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_MASK 0x20000UL /**< Bit mask for CMU_LFXOBUFCUR */
-#define _CMU_CTRL_LFXOBUFCUR_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOBUFCUR_DEFAULT (_CMU_CTRL_LFXOBUFCUR_DEFAULT << 17) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_SHIFT 18 /**< Shift value for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_MASK 0xC0000UL /**< Bit mask for CMU_LFXOTIMEOUT */
-#define _CMU_CTRL_LFXOTIMEOUT_8CYCLES 0x00000000UL /**< Mode 8CYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_1KCYCLES 0x00000001UL /**< Mode 1KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_16KCYCLES 0x00000002UL /**< Mode 16KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_LFXOTIMEOUT_32KCYCLES 0x00000003UL /**< Mode 32KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_8CYCLES (_CMU_CTRL_LFXOTIMEOUT_8CYCLES << 18) /**< Shifted mode 8CYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_1KCYCLES (_CMU_CTRL_LFXOTIMEOUT_1KCYCLES << 18) /**< Shifted mode 1KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_16KCYCLES (_CMU_CTRL_LFXOTIMEOUT_16KCYCLES << 18) /**< Shifted mode 16KCYCLES for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_DEFAULT (_CMU_CTRL_LFXOTIMEOUT_DEFAULT << 18) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_LFXOTIMEOUT_32KCYCLES (_CMU_CTRL_LFXOTIMEOUT_32KCYCLES << 18) /**< Shifted mode 32KCYCLES for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_SHIFT 20 /**< Shift value for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_MASK 0x700000UL /**< Bit mask for CMU_CLKOUTSEL0 */
-#define _CMU_CTRL_CLKOUTSEL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFRCO 0x00000000UL /**< Mode HFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFXO 0x00000001UL /**< Mode HFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK2 0x00000002UL /**< Mode HFCLK2 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK4 0x00000003UL /**< Mode HFCLK4 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK8 0x00000004UL /**< Mode HFCLK8 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_HFCLK16 0x00000005UL /**< Mode HFCLK16 for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_ULFRCO 0x00000006UL /**< Mode ULFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL0_AUXHFRCO 0x00000007UL /**< Mode AUXHFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_DEFAULT (_CMU_CTRL_CLKOUTSEL0_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFRCO (_CMU_CTRL_CLKOUTSEL0_HFRCO << 20) /**< Shifted mode HFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFXO (_CMU_CTRL_CLKOUTSEL0_HFXO << 20) /**< Shifted mode HFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK2 (_CMU_CTRL_CLKOUTSEL0_HFCLK2 << 20) /**< Shifted mode HFCLK2 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK4 (_CMU_CTRL_CLKOUTSEL0_HFCLK4 << 20) /**< Shifted mode HFCLK4 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK8 (_CMU_CTRL_CLKOUTSEL0_HFCLK8 << 20) /**< Shifted mode HFCLK8 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_HFCLK16 (_CMU_CTRL_CLKOUTSEL0_HFCLK16 << 20) /**< Shifted mode HFCLK16 for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_ULFRCO (_CMU_CTRL_CLKOUTSEL0_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL0_AUXHFRCO (_CMU_CTRL_CLKOUTSEL0_AUXHFRCO << 20) /**< Shifted mode AUXHFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_SHIFT 23 /**< Shift value for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_MASK 0x7800000UL /**< Bit mask for CMU_CLKOUTSEL1 */
-#define _CMU_CTRL_CLKOUTSEL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCO 0x00000000UL /**< Mode LFRCO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXO 0x00000001UL /**< Mode LFXO for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFCLK 0x00000002UL /**< Mode HFCLK for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFXOQ 0x00000003UL /**< Mode LFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFXOQ 0x00000004UL /**< Mode HFXOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_LFRCOQ 0x00000005UL /**< Mode LFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_HFRCOQ 0x00000006UL /**< Mode HFRCOQ for CMU_CTRL */
-#define _CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ 0x00000007UL /**< Mode AUXHFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_DEFAULT (_CMU_CTRL_CLKOUTSEL1_DEFAULT << 23) /**< Shifted mode DEFAULT for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCO (_CMU_CTRL_CLKOUTSEL1_LFRCO << 23) /**< Shifted mode LFRCO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXO (_CMU_CTRL_CLKOUTSEL1_LFXO << 23) /**< Shifted mode LFXO for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFCLK (_CMU_CTRL_CLKOUTSEL1_HFCLK << 23) /**< Shifted mode HFCLK for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFXOQ (_CMU_CTRL_CLKOUTSEL1_LFXOQ << 23) /**< Shifted mode LFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFXOQ (_CMU_CTRL_CLKOUTSEL1_HFXOQ << 23) /**< Shifted mode HFXOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_LFRCOQ (_CMU_CTRL_CLKOUTSEL1_LFRCOQ << 23) /**< Shifted mode LFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_HFRCOQ (_CMU_CTRL_CLKOUTSEL1_HFRCOQ << 23) /**< Shifted mode HFRCOQ for CMU_CTRL */
-#define CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ (_CMU_CTRL_CLKOUTSEL1_AUXHFRCOQ << 23) /**< Shifted mode AUXHFRCOQ for CMU_CTRL */
-
-/* Bit fields for CMU HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_SHIFT 0 /**< Shift value for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 (_CMU_HFCORECLKDIV_HFCORECLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV (0x1UL << 8) /**< Additional Division Factor For HFCORECLKLE */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_SHIFT 8 /**< Shift value for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_MASK 0x100UL /**< Bit mask for CMU_HFCORECLKLEDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 0x00000000UL /**< Mode DIV2 for CMU_HFCORECLKDIV */
-#define _CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 0x00000001UL /**< Mode DIV4 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV2 << 8) /**< Shifted mode DIV2 for CMU_HFCORECLKDIV */
-#define CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 (_CMU_HFCORECLKDIV_HFCORECLKLEDIV_DIV4 << 8) /**< Shifted mode DIV4 for CMU_HFCORECLKDIV */
-
-/* Bit fields for CMU HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_RESETVALUE 0x00000100UL /**< Default value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_MASK 0x0000010FUL /**< Mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_SHIFT 0 /**< Shift value for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_MASK 0xFUL /**< Bit mask for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 0x00000001UL /**< Mode HFCLK2 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 0x00000002UL /**< Mode HFCLK4 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 0x00000003UL /**< Mode HFCLK8 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 0x00000004UL /**< Mode HFCLK16 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 0x00000005UL /**< Mode HFCLK32 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 0x00000006UL /**< Mode HFCLK64 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 0x00000007UL /**< Mode HFCLK128 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 0x00000008UL /**< Mode HFCLK256 for CMU_HFPERCLKDIV */
-#define _CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 0x00000009UL /**< Mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKDIV_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK << 0) /**< Shifted mode HFCLK for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK2 << 0) /**< Shifted mode HFCLK2 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK4 << 0) /**< Shifted mode HFCLK4 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK8 << 0) /**< Shifted mode HFCLK8 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK16 << 0) /**< Shifted mode HFCLK16 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK32 << 0) /**< Shifted mode HFCLK32 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK64 << 0) /**< Shifted mode HFCLK64 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK128 << 0) /**< Shifted mode HFCLK128 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK256 << 0) /**< Shifted mode HFCLK256 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 (_CMU_HFPERCLKDIV_HFPERCLKDIV_HFCLK512 << 0) /**< Shifted mode HFCLK512 for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN (0x1UL << 8) /**< HFPERCLK Enable */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_SHIFT 8 /**< Shift value for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_MASK 0x100UL /**< Bit mask for CMU_HFPERCLKEN */
-#define _CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_HFPERCLKDIV */
-#define CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT (_CMU_HFPERCLKDIV_HFPERCLKEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKDIV */
-
-/* Bit fields for CMU HFRCOCTRL */
-#define _CMU_HFRCOCTRL_RESETVALUE 0x00000380UL /**< Default value for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_MASK 0x0001F7FFUL /**< Mask for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_HFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_TUNING_DEFAULT (_CMU_HFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_HFRCOCTRL_BAND_1MHZ 0x00000000UL /**< Mode 1MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_7MHZ 0x00000001UL /**< Mode 7MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_11MHZ 0x00000002UL /**< Mode 11MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_DEFAULT 0x00000003UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_14MHZ 0x00000003UL /**< Mode 14MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_BAND_21MHZ 0x00000004UL /**< Mode 21MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_1MHZ (_CMU_HFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_7MHZ (_CMU_HFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_11MHZ (_CMU_HFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_DEFAULT (_CMU_HFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_14MHZ (_CMU_HFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_BAND_21MHZ (_CMU_HFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_HFRCOCTRL */
-#define _CMU_HFRCOCTRL_SUDELAY_SHIFT 12 /**< Shift value for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_MASK 0x1F000UL /**< Bit mask for CMU_SUDELAY */
-#define _CMU_HFRCOCTRL_SUDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFRCOCTRL */
-#define CMU_HFRCOCTRL_SUDELAY_DEFAULT (_CMU_HFRCOCTRL_SUDELAY_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_HFRCOCTRL */
-
-/* Bit fields for CMU LFRCOCTRL */
-#define _CMU_LFRCOCTRL_RESETVALUE 0x00000040UL /**< Default value for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_MASK 0x0000007FUL /**< Mask for CMU_LFRCOCTRL */
-#define _CMU_LFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_MASK 0x7FUL /**< Bit mask for CMU_TUNING */
-#define _CMU_LFRCOCTRL_TUNING_DEFAULT 0x00000040UL /**< Mode DEFAULT for CMU_LFRCOCTRL */
-#define CMU_LFRCOCTRL_TUNING_DEFAULT (_CMU_LFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFRCOCTRL */
-
-/* Bit fields for CMU AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_RESETVALUE 0x00000080UL /**< Default value for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_MASK 0x000007FFUL /**< Mask for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_TUNING_SHIFT 0 /**< Shift value for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_MASK 0xFFUL /**< Bit mask for CMU_TUNING */
-#define _CMU_AUXHFRCOCTRL_TUNING_DEFAULT 0x00000080UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_TUNING_DEFAULT (_CMU_AUXHFRCOCTRL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_SHIFT 8 /**< Shift value for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_MASK 0x700UL /**< Bit mask for CMU_BAND */
-#define _CMU_AUXHFRCOCTRL_BAND_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_14MHZ 0x00000000UL /**< Mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_11MHZ 0x00000001UL /**< Mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_7MHZ 0x00000002UL /**< Mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_1MHZ 0x00000003UL /**< Mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define _CMU_AUXHFRCOCTRL_BAND_21MHZ 0x00000007UL /**< Mode 21MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_DEFAULT (_CMU_AUXHFRCOCTRL_BAND_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_14MHZ (_CMU_AUXHFRCOCTRL_BAND_14MHZ << 8) /**< Shifted mode 14MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_11MHZ (_CMU_AUXHFRCOCTRL_BAND_11MHZ << 8) /**< Shifted mode 11MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_7MHZ (_CMU_AUXHFRCOCTRL_BAND_7MHZ << 8) /**< Shifted mode 7MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_1MHZ (_CMU_AUXHFRCOCTRL_BAND_1MHZ << 8) /**< Shifted mode 1MHZ for CMU_AUXHFRCOCTRL */
-#define CMU_AUXHFRCOCTRL_BAND_21MHZ (_CMU_AUXHFRCOCTRL_BAND_21MHZ << 8) /**< Shifted mode 21MHZ for CMU_AUXHFRCOCTRL */
-
-/* Bit fields for CMU CALCTRL */
-#define _CMU_CALCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCTRL */
-#define _CMU_CALCTRL_MASK 0x0000007FUL /**< Mask for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_SHIFT 0 /**< Shift value for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_MASK 0x7UL /**< Bit mask for CMU_UPSEL */
-#define _CMU_CALCTRL_UPSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFXO 0x00000000UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFXO 0x00000001UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_HFRCO 0x00000002UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_UPSEL_AUXHFRCO 0x00000004UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_DEFAULT (_CMU_CALCTRL_UPSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFXO (_CMU_CALCTRL_UPSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFXO (_CMU_CALCTRL_UPSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_HFRCO (_CMU_CALCTRL_UPSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_LFRCO (_CMU_CALCTRL_UPSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_UPSEL_AUXHFRCO (_CMU_CALCTRL_UPSEL_AUXHFRCO << 0) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_SHIFT 3 /**< Shift value for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_MASK 0x38UL /**< Bit mask for CMU_DOWNSEL */
-#define _CMU_CALCTRL_DOWNSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFCLK 0x00000000UL /**< Mode HFCLK for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFXO 0x00000001UL /**< Mode HFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFXO 0x00000002UL /**< Mode LFXO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_HFRCO 0x00000003UL /**< Mode HFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_LFRCO 0x00000004UL /**< Mode LFRCO for CMU_CALCTRL */
-#define _CMU_CALCTRL_DOWNSEL_AUXHFRCO 0x00000005UL /**< Mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_DEFAULT (_CMU_CALCTRL_DOWNSEL_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFCLK (_CMU_CALCTRL_DOWNSEL_HFCLK << 3) /**< Shifted mode HFCLK for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFXO (_CMU_CALCTRL_DOWNSEL_HFXO << 3) /**< Shifted mode HFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFXO (_CMU_CALCTRL_DOWNSEL_LFXO << 3) /**< Shifted mode LFXO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_HFRCO (_CMU_CALCTRL_DOWNSEL_HFRCO << 3) /**< Shifted mode HFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_LFRCO (_CMU_CALCTRL_DOWNSEL_LFRCO << 3) /**< Shifted mode LFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_DOWNSEL_AUXHFRCO (_CMU_CALCTRL_DOWNSEL_AUXHFRCO << 3) /**< Shifted mode AUXHFRCO for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT (0x1UL << 6) /**< Continuous Calibration */
-#define _CMU_CALCTRL_CONT_SHIFT 6 /**< Shift value for CMU_CONT */
-#define _CMU_CALCTRL_CONT_MASK 0x40UL /**< Bit mask for CMU_CONT */
-#define _CMU_CALCTRL_CONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCTRL */
-#define CMU_CALCTRL_CONT_DEFAULT (_CMU_CALCTRL_CONT_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_CALCTRL */
-
-/* Bit fields for CMU CALCNT */
-#define _CMU_CALCNT_RESETVALUE 0x00000000UL /**< Default value for CMU_CALCNT */
-#define _CMU_CALCNT_MASK 0x000FFFFFUL /**< Mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_SHIFT 0 /**< Shift value for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_MASK 0xFFFFFUL /**< Bit mask for CMU_CALCNT */
-#define _CMU_CALCNT_CALCNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CALCNT */
-#define CMU_CALCNT_CALCNT_DEFAULT (_CMU_CALCNT_CALCNT_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CALCNT */
-
-/* Bit fields for CMU OSCENCMD */
-#define _CMU_OSCENCMD_RESETVALUE 0x00000000UL /**< Default value for CMU_OSCENCMD */
-#define _CMU_OSCENCMD_MASK 0x000003FFUL /**< Mask for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN (0x1UL << 0) /**< HFRCO Enable */
-#define _CMU_OSCENCMD_HFRCOEN_SHIFT 0 /**< Shift value for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_MASK 0x1UL /**< Bit mask for CMU_HFRCOEN */
-#define _CMU_OSCENCMD_HFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCOEN_DEFAULT (_CMU_OSCENCMD_HFRCOEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS (0x1UL << 1) /**< HFRCO Disable */
-#define _CMU_OSCENCMD_HFRCODIS_SHIFT 1 /**< Shift value for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_MASK 0x2UL /**< Bit mask for CMU_HFRCODIS */
-#define _CMU_OSCENCMD_HFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFRCODIS_DEFAULT (_CMU_OSCENCMD_HFRCODIS_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN (0x1UL << 2) /**< HFXO Enable */
-#define _CMU_OSCENCMD_HFXOEN_SHIFT 2 /**< Shift value for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_MASK 0x4UL /**< Bit mask for CMU_HFXOEN */
-#define _CMU_OSCENCMD_HFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXOEN_DEFAULT (_CMU_OSCENCMD_HFXOEN_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS (0x1UL << 3) /**< HFXO Disable */
-#define _CMU_OSCENCMD_HFXODIS_SHIFT 3 /**< Shift value for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_MASK 0x8UL /**< Bit mask for CMU_HFXODIS */
-#define _CMU_OSCENCMD_HFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_HFXODIS_DEFAULT (_CMU_OSCENCMD_HFXODIS_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN (0x1UL << 4) /**< AUXHFRCO Enable */
-#define _CMU_OSCENCMD_AUXHFRCOEN_SHIFT 4 /**< Shift value for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOEN */
-#define _CMU_OSCENCMD_AUXHFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCOEN_DEFAULT (_CMU_OSCENCMD_AUXHFRCOEN_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS (0x1UL << 5) /**< AUXHFRCO Disable */
-#define _CMU_OSCENCMD_AUXHFRCODIS_SHIFT 5 /**< Shift value for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCODIS */
-#define _CMU_OSCENCMD_AUXHFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_AUXHFRCODIS_DEFAULT (_CMU_OSCENCMD_AUXHFRCODIS_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN (0x1UL << 6) /**< LFRCO Enable */
-#define _CMU_OSCENCMD_LFRCOEN_SHIFT 6 /**< Shift value for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_MASK 0x40UL /**< Bit mask for CMU_LFRCOEN */
-#define _CMU_OSCENCMD_LFRCOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCOEN_DEFAULT (_CMU_OSCENCMD_LFRCOEN_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS (0x1UL << 7) /**< LFRCO Disable */
-#define _CMU_OSCENCMD_LFRCODIS_SHIFT 7 /**< Shift value for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_MASK 0x80UL /**< Bit mask for CMU_LFRCODIS */
-#define _CMU_OSCENCMD_LFRCODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFRCODIS_DEFAULT (_CMU_OSCENCMD_LFRCODIS_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN (0x1UL << 8) /**< LFXO Enable */
-#define _CMU_OSCENCMD_LFXOEN_SHIFT 8 /**< Shift value for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_MASK 0x100UL /**< Bit mask for CMU_LFXOEN */
-#define _CMU_OSCENCMD_LFXOEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXOEN_DEFAULT (_CMU_OSCENCMD_LFXOEN_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS (0x1UL << 9) /**< LFXO Disable */
-#define _CMU_OSCENCMD_LFXODIS_SHIFT 9 /**< Shift value for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_MASK 0x200UL /**< Bit mask for CMU_LFXODIS */
-#define _CMU_OSCENCMD_LFXODIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_OSCENCMD */
-#define CMU_OSCENCMD_LFXODIS_DEFAULT (_CMU_OSCENCMD_LFXODIS_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_OSCENCMD */
-
-/* Bit fields for CMU CMD */
-#define _CMU_CMD_RESETVALUE 0x00000000UL /**< Default value for CMU_CMD */
-#define _CMU_CMD_MASK 0x0000001FUL /**< Mask for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_SHIFT 0 /**< Shift value for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_MASK 0x7UL /**< Bit mask for CMU_HFCLKSEL */
-#define _CMU_CMD_HFCLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFRCO 0x00000001UL /**< Mode HFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_HFXO 0x00000002UL /**< Mode HFXO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFRCO 0x00000003UL /**< Mode LFRCO for CMU_CMD */
-#define _CMU_CMD_HFCLKSEL_LFXO 0x00000004UL /**< Mode LFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_DEFAULT (_CMU_CMD_HFCLKSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFRCO (_CMU_CMD_HFCLKSEL_HFRCO << 0) /**< Shifted mode HFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_HFXO (_CMU_CMD_HFCLKSEL_HFXO << 0) /**< Shifted mode HFXO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFRCO (_CMU_CMD_HFCLKSEL_LFRCO << 0) /**< Shifted mode LFRCO for CMU_CMD */
-#define CMU_CMD_HFCLKSEL_LFXO (_CMU_CMD_HFCLKSEL_LFXO << 0) /**< Shifted mode LFXO for CMU_CMD */
-#define CMU_CMD_CALSTART (0x1UL << 3) /**< Calibration Start */
-#define _CMU_CMD_CALSTART_SHIFT 3 /**< Shift value for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_MASK 0x8UL /**< Bit mask for CMU_CALSTART */
-#define _CMU_CMD_CALSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTART_DEFAULT (_CMU_CMD_CALSTART_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP (0x1UL << 4) /**< Calibration Stop */
-#define _CMU_CMD_CALSTOP_SHIFT 4 /**< Shift value for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_MASK 0x10UL /**< Bit mask for CMU_CALSTOP */
-#define _CMU_CMD_CALSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_CMD */
-#define CMU_CMD_CALSTOP_DEFAULT (_CMU_CMD_CALSTOP_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_CMD */
-
-/* Bit fields for CMU LFCLKSEL */
-#define _CMU_LFCLKSEL_RESETVALUE 0x00000005UL /**< Default value for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_MASK 0x0011000FUL /**< Mask for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_SHIFT 0 /**< Shift value for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_MASK 0x3UL /**< Bit mask for CMU_LFA */
-#define _CMU_LFCLKSEL_LFA_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DISABLED (_CMU_LFCLKSEL_LFA_DISABLED << 0) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_DEFAULT (_CMU_LFCLKSEL_LFA_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFRCO (_CMU_LFCLKSEL_LFA_LFRCO << 0) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_LFXO (_CMU_LFCLKSEL_LFA_LFXO << 0) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFA_HFCORECLKLEDIV2 << 0) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_SHIFT 2 /**< Shift value for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_MASK 0xCUL /**< Bit mask for CMU_LFB */
-#define _CMU_LFCLKSEL_LFB_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFRCO 0x00000001UL /**< Mode LFRCO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_LFXO 0x00000002UL /**< Mode LFXO for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 0x00000003UL /**< Mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DISABLED (_CMU_LFCLKSEL_LFB_DISABLED << 2) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_DEFAULT (_CMU_LFCLKSEL_LFB_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFRCO (_CMU_LFCLKSEL_LFB_LFRCO << 2) /**< Shifted mode LFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_LFXO (_CMU_LFCLKSEL_LFB_LFXO << 2) /**< Shifted mode LFXO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 (_CMU_LFCLKSEL_LFB_HFCORECLKLEDIV2 << 2) /**< Shifted mode HFCORECLKLEDIV2 for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE (0x1UL << 16) /**< Clock Select for LFA Extended */
-#define _CMU_LFCLKSEL_LFAE_SHIFT 16 /**< Shift value for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_MASK 0x10000UL /**< Bit mask for CMU_LFAE */
-#define _CMU_LFCLKSEL_LFAE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFAE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DEFAULT (_CMU_LFCLKSEL_LFAE_DEFAULT << 16) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_DISABLED (_CMU_LFCLKSEL_LFAE_DISABLED << 16) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFAE_ULFRCO (_CMU_LFCLKSEL_LFAE_ULFRCO << 16) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE (0x1UL << 20) /**< Clock Select for LFB Extended */
-#define _CMU_LFCLKSEL_LFBE_SHIFT 20 /**< Shift value for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_MASK 0x100000UL /**< Bit mask for CMU_LFBE */
-#define _CMU_LFCLKSEL_LFBE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_DISABLED 0x00000000UL /**< Mode DISABLED for CMU_LFCLKSEL */
-#define _CMU_LFCLKSEL_LFBE_ULFRCO 0x00000001UL /**< Mode ULFRCO for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DEFAULT (_CMU_LFCLKSEL_LFBE_DEFAULT << 20) /**< Shifted mode DEFAULT for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_DISABLED (_CMU_LFCLKSEL_LFBE_DISABLED << 20) /**< Shifted mode DISABLED for CMU_LFCLKSEL */
-#define CMU_LFCLKSEL_LFBE_ULFRCO (_CMU_LFCLKSEL_LFBE_ULFRCO << 20) /**< Shifted mode ULFRCO for CMU_LFCLKSEL */
-
-/* Bit fields for CMU STATUS */
-#define _CMU_STATUS_RESETVALUE 0x00000403UL /**< Default value for CMU_STATUS */
-#define _CMU_STATUS_MASK 0x00007FFFUL /**< Mask for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS (0x1UL << 0) /**< HFRCO Enable Status */
-#define _CMU_STATUS_HFRCOENS_SHIFT 0 /**< Shift value for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_MASK 0x1UL /**< Bit mask for CMU_HFRCOENS */
-#define _CMU_STATUS_HFRCOENS_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOENS_DEFAULT (_CMU_STATUS_HFRCOENS_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY (0x1UL << 1) /**< HFRCO Ready */
-#define _CMU_STATUS_HFRCORDY_SHIFT 1 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_MASK 0x2UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_STATUS_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCORDY_DEFAULT (_CMU_STATUS_HFRCORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS (0x1UL << 2) /**< HFXO Enable Status */
-#define _CMU_STATUS_HFXOENS_SHIFT 2 /**< Shift value for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_MASK 0x4UL /**< Bit mask for CMU_HFXOENS */
-#define _CMU_STATUS_HFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOENS_DEFAULT (_CMU_STATUS_HFXOENS_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY (0x1UL << 3) /**< HFXO Ready */
-#define _CMU_STATUS_HFXORDY_SHIFT 3 /**< Shift value for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_MASK 0x8UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_STATUS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXORDY_DEFAULT (_CMU_STATUS_HFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS (0x1UL << 4) /**< AUXHFRCO Enable Status */
-#define _CMU_STATUS_AUXHFRCOENS_SHIFT 4 /**< Shift value for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCOENS */
-#define _CMU_STATUS_AUXHFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCOENS_DEFAULT (_CMU_STATUS_AUXHFRCOENS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY (0x1UL << 5) /**< AUXHFRCO Ready */
-#define _CMU_STATUS_AUXHFRCORDY_SHIFT 5 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_MASK 0x20UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_STATUS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_AUXHFRCORDY_DEFAULT (_CMU_STATUS_AUXHFRCORDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS (0x1UL << 6) /**< LFRCO Enable Status */
-#define _CMU_STATUS_LFRCOENS_SHIFT 6 /**< Shift value for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_MASK 0x40UL /**< Bit mask for CMU_LFRCOENS */
-#define _CMU_STATUS_LFRCOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOENS_DEFAULT (_CMU_STATUS_LFRCOENS_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY (0x1UL << 7) /**< LFRCO Ready */
-#define _CMU_STATUS_LFRCORDY_SHIFT 7 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_MASK 0x80UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_STATUS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCORDY_DEFAULT (_CMU_STATUS_LFRCORDY_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS (0x1UL << 8) /**< LFXO Enable Status */
-#define _CMU_STATUS_LFXOENS_SHIFT 8 /**< Shift value for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_MASK 0x100UL /**< Bit mask for CMU_LFXOENS */
-#define _CMU_STATUS_LFXOENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOENS_DEFAULT (_CMU_STATUS_LFXOENS_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY (0x1UL << 9) /**< LFXO Ready */
-#define _CMU_STATUS_LFXORDY_SHIFT 9 /**< Shift value for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_MASK 0x200UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_STATUS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXORDY_DEFAULT (_CMU_STATUS_LFXORDY_DEFAULT << 9) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL (0x1UL << 10) /**< HFRCO Selected */
-#define _CMU_STATUS_HFRCOSEL_SHIFT 10 /**< Shift value for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_MASK 0x400UL /**< Bit mask for CMU_HFRCOSEL */
-#define _CMU_STATUS_HFRCOSEL_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFRCOSEL_DEFAULT (_CMU_STATUS_HFRCOSEL_DEFAULT << 10) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL (0x1UL << 11) /**< HFXO Selected */
-#define _CMU_STATUS_HFXOSEL_SHIFT 11 /**< Shift value for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_MASK 0x800UL /**< Bit mask for CMU_HFXOSEL */
-#define _CMU_STATUS_HFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_HFXOSEL_DEFAULT (_CMU_STATUS_HFXOSEL_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL (0x1UL << 12) /**< LFRCO Selected */
-#define _CMU_STATUS_LFRCOSEL_SHIFT 12 /**< Shift value for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_MASK 0x1000UL /**< Bit mask for CMU_LFRCOSEL */
-#define _CMU_STATUS_LFRCOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFRCOSEL_DEFAULT (_CMU_STATUS_LFRCOSEL_DEFAULT << 12) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL (0x1UL << 13) /**< LFXO Selected */
-#define _CMU_STATUS_LFXOSEL_SHIFT 13 /**< Shift value for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_MASK 0x2000UL /**< Bit mask for CMU_LFXOSEL */
-#define _CMU_STATUS_LFXOSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_LFXOSEL_DEFAULT (_CMU_STATUS_LFXOSEL_DEFAULT << 13) /**< Shifted mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY (0x1UL << 14) /**< Calibration Busy */
-#define _CMU_STATUS_CALBSY_SHIFT 14 /**< Shift value for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_MASK 0x4000UL /**< Bit mask for CMU_CALBSY */
-#define _CMU_STATUS_CALBSY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_STATUS */
-#define CMU_STATUS_CALBSY_DEFAULT (_CMU_STATUS_CALBSY_DEFAULT << 14) /**< Shifted mode DEFAULT for CMU_STATUS */
-
-/* Bit fields for CMU IF */
-#define _CMU_IF_RESETVALUE 0x00000001UL /**< Default value for CMU_IF */
-#define _CMU_IF_MASK 0x0000007FUL /**< Mask for CMU_IF */
-#define CMU_IF_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag */
-#define _CMU_IF_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IF_HFRCORDY_DEFAULT 0x00000001UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFRCORDY_DEFAULT (_CMU_IF_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag */
-#define _CMU_IF_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IF_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_HFXORDY_DEFAULT (_CMU_IF_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag */
-#define _CMU_IF_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IF_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFRCORDY_DEFAULT (_CMU_IF_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag */
-#define _CMU_IF_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IF_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_LFXORDY_DEFAULT (_CMU_IF_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag */
-#define _CMU_IF_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IF_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_AUXHFRCORDY_DEFAULT (_CMU_IF_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag */
-#define _CMU_IF_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IF_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IF_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALRDY_DEFAULT (_CMU_IF_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag */
-#define _CMU_IF_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IF_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IF_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IF */
-#define CMU_IF_CALOF_DEFAULT (_CMU_IF_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IF */
-
-/* Bit fields for CMU IFS */
-#define _CMU_IFS_RESETVALUE 0x00000000UL /**< Default value for CMU_IFS */
-#define _CMU_IFS_MASK 0x0000007FUL /**< Mask for CMU_IFS */
-#define CMU_IFS_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFS_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFRCORDY_DEFAULT (_CMU_IFS_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFS_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_HFXORDY_DEFAULT (_CMU_IFS_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFS_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFRCORDY_DEFAULT (_CMU_IFS_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Set */
-#define _CMU_IFS_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFS_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_LFXORDY_DEFAULT (_CMU_IFS_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Set */
-#define _CMU_IFS_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFS_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_AUXHFRCORDY_DEFAULT (_CMU_IFS_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Set */
-#define _CMU_IFS_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFS_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALRDY_DEFAULT (_CMU_IFS_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Set */
-#define _CMU_IFS_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFS_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFS_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFS */
-#define CMU_IFS_CALOF_DEFAULT (_CMU_IFS_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFS */
-
-/* Bit fields for CMU IFC */
-#define _CMU_IFC_RESETVALUE 0x00000000UL /**< Default value for CMU_IFC */
-#define _CMU_IFC_MASK 0x0000007FUL /**< Mask for CMU_IFC */
-#define CMU_IFC_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IFC_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFRCORDY_DEFAULT (_CMU_IFC_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IFC_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_HFXORDY_DEFAULT (_CMU_IFC_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IFC_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFRCORDY_DEFAULT (_CMU_IFC_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Flag Clear */
-#define _CMU_IFC_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IFC_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_LFXORDY_DEFAULT (_CMU_IFC_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Flag Clear */
-#define _CMU_IFC_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IFC_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_AUXHFRCORDY_DEFAULT (_CMU_IFC_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Flag Clear */
-#define _CMU_IFC_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IFC_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALRDY_DEFAULT (_CMU_IFC_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Flag Clear */
-#define _CMU_IFC_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IFC_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IFC_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IFC */
-#define CMU_IFC_CALOF_DEFAULT (_CMU_IFC_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IFC */
-
-/* Bit fields for CMU IEN */
-#define _CMU_IEN_RESETVALUE 0x00000000UL /**< Default value for CMU_IEN */
-#define _CMU_IEN_MASK 0x0000007FUL /**< Mask for CMU_IEN */
-#define CMU_IEN_HFRCORDY (0x1UL << 0) /**< HFRCO Ready Interrupt Enable */
-#define _CMU_IEN_HFRCORDY_SHIFT 0 /**< Shift value for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_MASK 0x1UL /**< Bit mask for CMU_HFRCORDY */
-#define _CMU_IEN_HFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFRCORDY_DEFAULT (_CMU_IEN_HFRCORDY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY (0x1UL << 1) /**< HFXO Ready Interrupt Enable */
-#define _CMU_IEN_HFXORDY_SHIFT 1 /**< Shift value for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_MASK 0x2UL /**< Bit mask for CMU_HFXORDY */
-#define _CMU_IEN_HFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_HFXORDY_DEFAULT (_CMU_IEN_HFXORDY_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY (0x1UL << 2) /**< LFRCO Ready Interrupt Enable */
-#define _CMU_IEN_LFRCORDY_SHIFT 2 /**< Shift value for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_MASK 0x4UL /**< Bit mask for CMU_LFRCORDY */
-#define _CMU_IEN_LFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFRCORDY_DEFAULT (_CMU_IEN_LFRCORDY_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY (0x1UL << 3) /**< LFXO Ready Interrupt Enable */
-#define _CMU_IEN_LFXORDY_SHIFT 3 /**< Shift value for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_MASK 0x8UL /**< Bit mask for CMU_LFXORDY */
-#define _CMU_IEN_LFXORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_LFXORDY_DEFAULT (_CMU_IEN_LFXORDY_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY (0x1UL << 4) /**< AUXHFRCO Ready Interrupt Enable */
-#define _CMU_IEN_AUXHFRCORDY_SHIFT 4 /**< Shift value for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_MASK 0x10UL /**< Bit mask for CMU_AUXHFRCORDY */
-#define _CMU_IEN_AUXHFRCORDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_AUXHFRCORDY_DEFAULT (_CMU_IEN_AUXHFRCORDY_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY (0x1UL << 5) /**< Calibration Ready Interrupt Enable */
-#define _CMU_IEN_CALRDY_SHIFT 5 /**< Shift value for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_MASK 0x20UL /**< Bit mask for CMU_CALRDY */
-#define _CMU_IEN_CALRDY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALRDY_DEFAULT (_CMU_IEN_CALRDY_DEFAULT << 5) /**< Shifted mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF (0x1UL << 6) /**< Calibration Overflow Interrupt Enable */
-#define _CMU_IEN_CALOF_SHIFT 6 /**< Shift value for CMU_CALOF */
-#define _CMU_IEN_CALOF_MASK 0x40UL /**< Bit mask for CMU_CALOF */
-#define _CMU_IEN_CALOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_IEN */
-#define CMU_IEN_CALOF_DEFAULT (_CMU_IEN_CALOF_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_IEN */
-
-/* Bit fields for CMU HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFCORECLKEN0 */
-#define _CMU_HFCORECLKEN0_MASK 0x00000007UL /**< Mask for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_AES (0x1UL << 0) /**< Advanced Encryption Standard Accelerator Clock Enable */
-#define _CMU_HFCORECLKEN0_AES_SHIFT 0 /**< Shift value for CMU_AES */
-#define _CMU_HFCORECLKEN0_AES_MASK 0x1UL /**< Bit mask for CMU_AES */
-#define _CMU_HFCORECLKEN0_AES_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_AES_DEFAULT (_CMU_HFCORECLKEN0_AES_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA (0x1UL << 1) /**< Direct Memory Access Controller Clock Enable */
-#define _CMU_HFCORECLKEN0_DMA_SHIFT 1 /**< Shift value for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_MASK 0x2UL /**< Bit mask for CMU_DMA */
-#define _CMU_HFCORECLKEN0_DMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_DMA_DEFAULT (_CMU_HFCORECLKEN0_DMA_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE (0x1UL << 2) /**< Low Energy Peripheral Interface Clock Enable */
-#define _CMU_HFCORECLKEN0_LE_SHIFT 2 /**< Shift value for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_MASK 0x4UL /**< Bit mask for CMU_LE */
-#define _CMU_HFCORECLKEN0_LE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFCORECLKEN0 */
-#define CMU_HFCORECLKEN0_LE_DEFAULT (_CMU_HFCORECLKEN0_LE_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFCORECLKEN0 */
-
-/* Bit fields for CMU HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_HFPERCLKEN0 */
-#define _CMU_HFPERCLKEN0_MASK 0x00000DDFUL /**< Mask for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0 (0x1UL << 0) /**< Timer 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER0_SHIFT 0 /**< Shift value for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_MASK 0x1UL /**< Bit mask for CMU_TIMER0 */
-#define _CMU_HFPERCLKEN0_TIMER0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER0_DEFAULT (_CMU_HFPERCLKEN0_TIMER0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1 (0x1UL << 1) /**< Timer 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_TIMER1_SHIFT 1 /**< Shift value for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_MASK 0x2UL /**< Bit mask for CMU_TIMER1 */
-#define _CMU_HFPERCLKEN0_TIMER1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_TIMER1_DEFAULT (_CMU_HFPERCLKEN0_TIMER1_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0 (0x1UL << 2) /**< Analog Comparator 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_ACMP0_SHIFT 2 /**< Shift value for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_MASK 0x4UL /**< Bit mask for CMU_ACMP0 */
-#define _CMU_HFPERCLKEN0_ACMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ACMP0_DEFAULT (_CMU_HFPERCLKEN0_ACMP0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1 (0x1UL << 3) /**< Universal Synchronous/Asynchronous Receiver/Transmitter 1 Clock Enable */
-#define _CMU_HFPERCLKEN0_USART1_SHIFT 3 /**< Shift value for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_MASK 0x8UL /**< Bit mask for CMU_USART1 */
-#define _CMU_HFPERCLKEN0_USART1_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_USART1_DEFAULT (_CMU_HFPERCLKEN0_USART1_DEFAULT << 3) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS (0x1UL << 4) /**< Peripheral Reflex System Clock Enable */
-#define _CMU_HFPERCLKEN0_PRS_SHIFT 4 /**< Shift value for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_MASK 0x10UL /**< Bit mask for CMU_PRS */
-#define _CMU_HFPERCLKEN0_PRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_PRS_DEFAULT (_CMU_HFPERCLKEN0_PRS_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_IDAC0 (0x1UL << 6) /**< Current Digital to Analog Converter 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_IDAC0_SHIFT 6 /**< Shift value for CMU_IDAC0 */
-#define _CMU_HFPERCLKEN0_IDAC0_MASK 0x40UL /**< Bit mask for CMU_IDAC0 */
-#define _CMU_HFPERCLKEN0_IDAC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_IDAC0_DEFAULT (_CMU_HFPERCLKEN0_IDAC0_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO (0x1UL << 7) /**< General purpose Input/Output Clock Enable */
-#define _CMU_HFPERCLKEN0_GPIO_SHIFT 7 /**< Shift value for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_MASK 0x80UL /**< Bit mask for CMU_GPIO */
-#define _CMU_HFPERCLKEN0_GPIO_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_GPIO_DEFAULT (_CMU_HFPERCLKEN0_GPIO_DEFAULT << 7) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP (0x1UL << 8) /**< Voltage Comparator Clock Enable */
-#define _CMU_HFPERCLKEN0_VCMP_SHIFT 8 /**< Shift value for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_MASK 0x100UL /**< Bit mask for CMU_VCMP */
-#define _CMU_HFPERCLKEN0_VCMP_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_VCMP_DEFAULT (_CMU_HFPERCLKEN0_VCMP_DEFAULT << 8) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ADC0 (0x1UL << 10) /**< Analog to Digital Converter 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_ADC0_SHIFT 10 /**< Shift value for CMU_ADC0 */
-#define _CMU_HFPERCLKEN0_ADC0_MASK 0x400UL /**< Bit mask for CMU_ADC0 */
-#define _CMU_HFPERCLKEN0_ADC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_ADC0_DEFAULT (_CMU_HFPERCLKEN0_ADC0_DEFAULT << 10) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0 (0x1UL << 11) /**< I2C 0 Clock Enable */
-#define _CMU_HFPERCLKEN0_I2C0_SHIFT 11 /**< Shift value for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_MASK 0x800UL /**< Bit mask for CMU_I2C0 */
-#define _CMU_HFPERCLKEN0_I2C0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_HFPERCLKEN0 */
-#define CMU_HFPERCLKEN0_I2C0_DEFAULT (_CMU_HFPERCLKEN0_I2C0_DEFAULT << 11) /**< Shifted mode DEFAULT for CMU_HFPERCLKEN0 */
-
-/* Bit fields for CMU SYNCBUSY */
-#define _CMU_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for CMU_SYNCBUSY */
-#define _CMU_SYNCBUSY_MASK 0x00000055UL /**< Mask for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0 (0x1UL << 0) /**< Low Frequency A Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFACLKEN0_SHIFT 0 /**< Shift value for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_MASK 0x1UL /**< Bit mask for CMU_LFACLKEN0 */
-#define _CMU_SYNCBUSY_LFACLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFACLKEN0_DEFAULT (_CMU_SYNCBUSY_LFACLKEN0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0 (0x1UL << 2) /**< Low Frequency A Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFAPRESC0_SHIFT 2 /**< Shift value for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_MASK 0x4UL /**< Bit mask for CMU_LFAPRESC0 */
-#define _CMU_SYNCBUSY_LFAPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFAPRESC0_DEFAULT (_CMU_SYNCBUSY_LFAPRESC0_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0 (0x1UL << 4) /**< Low Frequency B Clock Enable 0 Busy */
-#define _CMU_SYNCBUSY_LFBCLKEN0_SHIFT 4 /**< Shift value for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_MASK 0x10UL /**< Bit mask for CMU_LFBCLKEN0 */
-#define _CMU_SYNCBUSY_LFBCLKEN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBCLKEN0_DEFAULT (_CMU_SYNCBUSY_LFBCLKEN0_DEFAULT << 4) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0 (0x1UL << 6) /**< Low Frequency B Prescaler 0 Busy */
-#define _CMU_SYNCBUSY_LFBPRESC0_SHIFT 6 /**< Shift value for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_MASK 0x40UL /**< Bit mask for CMU_LFBPRESC0 */
-#define _CMU_SYNCBUSY_LFBPRESC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_SYNCBUSY */
-#define CMU_SYNCBUSY_LFBPRESC0_DEFAULT (_CMU_SYNCBUSY_LFBPRESC0_DEFAULT << 6) /**< Shifted mode DEFAULT for CMU_SYNCBUSY */
-
-/* Bit fields for CMU FREEZE */
-#define _CMU_FREEZE_RESETVALUE 0x00000000UL /**< Default value for CMU_FREEZE */
-#define _CMU_FREEZE_MASK 0x00000001UL /**< Mask for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _CMU_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for CMU_REGFREEZE */
-#define _CMU_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for CMU_FREEZE */
-#define _CMU_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_DEFAULT (_CMU_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_UPDATE (_CMU_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for CMU_FREEZE */
-#define CMU_FREEZE_REGFREEZE_FREEZE (_CMU_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for CMU_FREEZE */
-
-/* Bit fields for CMU LFACLKEN0 */
-#define _CMU_LFACLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFACLKEN0 */
-#define _CMU_LFACLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC (0x1UL << 0) /**< Real-Time Counter Clock Enable */
-#define _CMU_LFACLKEN0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_MASK 0x1UL /**< Bit mask for CMU_RTC */
-#define _CMU_LFACLKEN0_RTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFACLKEN0 */
-#define CMU_LFACLKEN0_RTC_DEFAULT (_CMU_LFACLKEN0_RTC_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFACLKEN0 */
-
-/* Bit fields for CMU LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBCLKEN0 */
-#define _CMU_LFBCLKEN0_MASK 0x00000001UL /**< Mask for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0 (0x1UL << 0) /**< Low Energy UART 0 Clock Enable */
-#define _CMU_LFBCLKEN0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_MASK 0x1UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBCLKEN0_LEUART0_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LFBCLKEN0 */
-#define CMU_LFBCLKEN0_LEUART0_DEFAULT (_CMU_LFBCLKEN0_LEUART0_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LFBCLKEN0 */
-
-/* Bit fields for CMU LFAPRESC0 */
-#define _CMU_LFAPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_MASK 0x0000000FUL /**< Mask for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_SHIFT 0 /**< Shift value for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_MASK 0xFUL /**< Bit mask for CMU_RTC */
-#define _CMU_LFAPRESC0_RTC_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16 0x00000004UL /**< Mode DIV16 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32 0x00000005UL /**< Mode DIV32 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV64 0x00000006UL /**< Mode DIV64 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV128 0x00000007UL /**< Mode DIV128 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV256 0x00000008UL /**< Mode DIV256 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV512 0x00000009UL /**< Mode DIV512 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV1024 0x0000000AUL /**< Mode DIV1024 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV2048 0x0000000BUL /**< Mode DIV2048 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV4096 0x0000000CUL /**< Mode DIV4096 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV8192 0x0000000DUL /**< Mode DIV8192 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV16384 0x0000000EUL /**< Mode DIV16384 for CMU_LFAPRESC0 */
-#define _CMU_LFAPRESC0_RTC_DIV32768 0x0000000FUL /**< Mode DIV32768 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1 (_CMU_LFAPRESC0_RTC_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2 (_CMU_LFAPRESC0_RTC_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4 (_CMU_LFAPRESC0_RTC_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8 (_CMU_LFAPRESC0_RTC_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16 (_CMU_LFAPRESC0_RTC_DIV16 << 0) /**< Shifted mode DIV16 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32 (_CMU_LFAPRESC0_RTC_DIV32 << 0) /**< Shifted mode DIV32 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV64 (_CMU_LFAPRESC0_RTC_DIV64 << 0) /**< Shifted mode DIV64 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV128 (_CMU_LFAPRESC0_RTC_DIV128 << 0) /**< Shifted mode DIV128 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV256 (_CMU_LFAPRESC0_RTC_DIV256 << 0) /**< Shifted mode DIV256 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV512 (_CMU_LFAPRESC0_RTC_DIV512 << 0) /**< Shifted mode DIV512 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV1024 (_CMU_LFAPRESC0_RTC_DIV1024 << 0) /**< Shifted mode DIV1024 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV2048 (_CMU_LFAPRESC0_RTC_DIV2048 << 0) /**< Shifted mode DIV2048 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV4096 (_CMU_LFAPRESC0_RTC_DIV4096 << 0) /**< Shifted mode DIV4096 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV8192 (_CMU_LFAPRESC0_RTC_DIV8192 << 0) /**< Shifted mode DIV8192 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV16384 (_CMU_LFAPRESC0_RTC_DIV16384 << 0) /**< Shifted mode DIV16384 for CMU_LFAPRESC0 */
-#define CMU_LFAPRESC0_RTC_DIV32768 (_CMU_LFAPRESC0_RTC_DIV32768 << 0) /**< Shifted mode DIV32768 for CMU_LFAPRESC0 */
-
-/* Bit fields for CMU LFBPRESC0 */
-#define _CMU_LFBPRESC0_RESETVALUE 0x00000000UL /**< Default value for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_MASK 0x00000003UL /**< Mask for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_SHIFT 0 /**< Shift value for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_MASK 0x3UL /**< Bit mask for CMU_LEUART0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV1 0x00000000UL /**< Mode DIV1 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV2 0x00000001UL /**< Mode DIV2 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV4 0x00000002UL /**< Mode DIV4 for CMU_LFBPRESC0 */
-#define _CMU_LFBPRESC0_LEUART0_DIV8 0x00000003UL /**< Mode DIV8 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV1 (_CMU_LFBPRESC0_LEUART0_DIV1 << 0) /**< Shifted mode DIV1 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV2 (_CMU_LFBPRESC0_LEUART0_DIV2 << 0) /**< Shifted mode DIV2 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV4 (_CMU_LFBPRESC0_LEUART0_DIV4 << 0) /**< Shifted mode DIV4 for CMU_LFBPRESC0 */
-#define CMU_LFBPRESC0_LEUART0_DIV8 (_CMU_LFBPRESC0_LEUART0_DIV8 << 0) /**< Shifted mode DIV8 for CMU_LFBPRESC0 */
-
-/* Bit fields for CMU PCNTCTRL */
-#define _CMU_PCNTCTRL_RESETVALUE 0x00000000UL /**< Default value for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_MASK 0x00000003UL /**< Mask for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN (0x1UL << 0) /**< PCNT0 Clock Enable */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_SHIFT 0 /**< Shift value for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_MASK 0x1UL /**< Bit mask for CMU_PCNT0CLKEN */
-#define _CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL (0x1UL << 1) /**< PCNT0 Clock Select */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_SHIFT 1 /**< Shift value for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_MASK 0x2UL /**< Bit mask for CMU_PCNT0CLKSEL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK 0x00000000UL /**< Mode LFACLK for CMU_PCNTCTRL */
-#define _CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 0x00000001UL /**< Mode PCNT0S0 for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT (_CMU_PCNTCTRL_PCNT0CLKSEL_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK (_CMU_PCNTCTRL_PCNT0CLKSEL_LFACLK << 1) /**< Shifted mode LFACLK for CMU_PCNTCTRL */
-#define CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 (_CMU_PCNTCTRL_PCNT0CLKSEL_PCNT0S0 << 1) /**< Shifted mode PCNT0S0 for CMU_PCNTCTRL */
-
-/* Bit fields for CMU ROUTE */
-#define _CMU_ROUTE_RESETVALUE 0x00000000UL /**< Default value for CMU_ROUTE */
-#define _CMU_ROUTE_MASK 0x0000001FUL /**< Mask for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN (0x1UL << 0) /**< CLKOUT0 Pin Enable */
-#define _CMU_ROUTE_CLKOUT0PEN_SHIFT 0 /**< Shift value for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_MASK 0x1UL /**< Bit mask for CMU_CLKOUT0PEN */
-#define _CMU_ROUTE_CLKOUT0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT0PEN_DEFAULT (_CMU_ROUTE_CLKOUT0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN (0x1UL << 1) /**< CLKOUT1 Pin Enable */
-#define _CMU_ROUTE_CLKOUT1PEN_SHIFT 1 /**< Shift value for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_MASK 0x2UL /**< Bit mask for CMU_CLKOUT1PEN */
-#define _CMU_ROUTE_CLKOUT1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_CLKOUT1PEN_DEFAULT (_CMU_ROUTE_CLKOUT1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_SHIFT 2 /**< Shift value for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_MASK 0x1CUL /**< Bit mask for CMU_LOCATION */
-#define _CMU_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for CMU_ROUTE */
-#define _CMU_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC0 (_CMU_ROUTE_LOCATION_LOC0 << 2) /**< Shifted mode LOC0 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_DEFAULT (_CMU_ROUTE_LOCATION_DEFAULT << 2) /**< Shifted mode DEFAULT for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC1 (_CMU_ROUTE_LOCATION_LOC1 << 2) /**< Shifted mode LOC1 for CMU_ROUTE */
-#define CMU_ROUTE_LOCATION_LOC2 (_CMU_ROUTE_LOCATION_LOC2 << 2) /**< Shifted mode LOC2 for CMU_ROUTE */
-
-/* Bit fields for CMU LOCK */
-#define _CMU_LOCK_RESETVALUE 0x00000000UL /**< Default value for CMU_LOCK */
-#define _CMU_LOCK_MASK 0x0000FFFFUL /**< Mask for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for CMU_LOCKKEY */
-#define _CMU_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for CMU_LOCK */
-#define _CMU_LOCK_LOCKKEY_UNLOCK 0x0000580EUL /**< Mode UNLOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_DEFAULT (_CMU_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCK (_CMU_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCKED (_CMU_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_LOCKED (_CMU_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for CMU_LOCK */
-#define CMU_LOCK_LOCKKEY_UNLOCK (_CMU_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for CMU_LOCK */
-
-/** @} End of group EFM32ZG_CMU */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_devinfo.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_devinfo.h
deleted file mode 100644
index 8dd0cc8f04..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_devinfo.h
+++ /dev/null
@@ -1,159 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_DEVINFO register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_DEVINFO
- * @{
- ******************************************************************************/
-typedef struct {
- __IM uint32_t CAL; /**< Calibration temperature and checksum */
- __IM uint32_t ADC0CAL0; /**< ADC0 Calibration register 0 */
- __IM uint32_t ADC0CAL1; /**< ADC0 Calibration register 1 */
- __IM uint32_t ADC0CAL2; /**< ADC0 Calibration register 2 */
- uint32_t RESERVED0[2U]; /**< Reserved */
- __IM uint32_t IDAC0CAL0; /**< IDAC0 calibration register */
- uint32_t RESERVED1[2U]; /**< Reserved */
- __IM uint32_t AUXHFRCOCAL0; /**< AUXHFRCO calibration register 0 */
- __IM uint32_t AUXHFRCOCAL1; /**< AUXHFRCO calibration register 1 */
- __IM uint32_t HFRCOCAL0; /**< HFRCO calibration register 0 */
- __IM uint32_t HFRCOCAL1; /**< HFRCO calibration register 1 */
- __IM uint32_t MEMINFO; /**< Memory information */
- uint32_t RESERVED2[2U]; /**< Reserved */
- __IM uint32_t UNIQUEL; /**< Low 32 bits of device unique number */
- __IM uint32_t UNIQUEH; /**< High 32 bits of device unique number */
- __IM uint32_t MSIZE; /**< Flash and SRAM Memory size in KiloBytes */
- __IM uint32_t PART; /**< Part description */
-} DEVINFO_TypeDef; /** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_DEVINFO_BitFields
- * @{
- ******************************************************************************/
-/* Bit fields for EFM32ZG_DEVINFO */
-#define _DEVINFO_CAL_CRC_MASK 0x0000FFFFUL /**< Integrity CRC checksum mask */
-#define _DEVINFO_CAL_CRC_SHIFT 0 /**< Integrity CRC checksum shift */
-#define _DEVINFO_CAL_TEMP_MASK 0x00FF0000UL /**< Calibration temperature, DegC, mask */
-#define _DEVINFO_CAL_TEMP_SHIFT 16 /**< Calibration temperature shift */
-#define _DEVINFO_ADC0CAL0_1V25_GAIN_MASK 0x00007F00UL /**< Gain for 1V25 reference, mask */
-#define _DEVINFO_ADC0CAL0_1V25_GAIN_SHIFT 8 /**< Gain for 1V25 reference, shift */
-#define _DEVINFO_ADC0CAL0_1V25_OFFSET_MASK 0x0000007FUL /**< Offset for 1V25 reference, mask */
-#define _DEVINFO_ADC0CAL0_1V25_OFFSET_SHIFT 0 /**< Offset for 1V25 reference, shift */
-#define _DEVINFO_ADC0CAL0_2V5_GAIN_MASK 0x7F000000UL /**< Gain for 2V5 reference, mask */
-#define _DEVINFO_ADC0CAL0_2V5_GAIN_SHIFT 24 /**< Gain for 2V5 reference, shift */
-#define _DEVINFO_ADC0CAL0_2V5_OFFSET_MASK 0x007F0000UL /**< Offset for 2V5 reference, mask */
-#define _DEVINFO_ADC0CAL0_2V5_OFFSET_SHIFT 16 /**< Offset for 2V5 reference, shift */
-#define _DEVINFO_ADC0CAL1_VDD_GAIN_MASK 0x00007F00UL /**< Gain for VDD reference, mask */
-#define _DEVINFO_ADC0CAL1_VDD_GAIN_SHIFT 8 /**< Gain for VDD reference, shift */
-#define _DEVINFO_ADC0CAL1_VDD_OFFSET_MASK 0x0000007FUL /**< Offset for VDD reference, mask */
-#define _DEVINFO_ADC0CAL1_VDD_OFFSET_SHIFT 0 /**< Offset for VDD reference, shift */
-#define _DEVINFO_ADC0CAL1_5VDIFF_GAIN_MASK 0x7F000000UL /**< Gain 5VDIFF for 5VDIFF reference, mask */
-#define _DEVINFO_ADC0CAL1_5VDIFF_GAIN_SHIFT 24 /**< Gain for 5VDIFF reference, mask */
-#define _DEVINFO_ADC0CAL1_5VDIFF_OFFSET_MASK 0x007F0000UL /**< Offset for 5VDIFF reference, mask */
-#define _DEVINFO_ADC0CAL1_5VDIFF_OFFSET_SHIFT 16 /**< Offset for 5VDIFF reference, shift */
-#define _DEVINFO_ADC0CAL2_2XVDDVSS_OFFSET_MASK 0x0000007FUL /**< Offset for 2XVDDVSS reference, mask */
-#define _DEVINFO_ADC0CAL2_2XVDDVSS_OFFSET_SHIFT 0 /**< Offset for 2XVDDVSS reference, shift */
-#define _DEVINFO_ADC0CAL2_TEMP1V25_MASK 0xFFF00000UL /**< Temperature reading at 1V25 reference, mask */
-#define _DEVINFO_ADC0CAL2_TEMP1V25_SHIFT 20 /**< Temperature reading at 1V25 reference, DegC */
-#define _DEVINFO_IDAC0CAL0_RANGE0_MASK 0x000000FFUL /**< Current range 0 tuning value for IDAC0 mask */
-#define _DEVINFO_IDAC0CAL0_RANGE0_SHIFT 0 /**< Current range 0 tuning value for IDAC0 shift */
-#define _DEVINFO_IDAC0CAL0_RANGE1_MASK 0x0000FF00UL /**< Current range 1 tuning value for IDAC0 mask */
-#define _DEVINFO_IDAC0CAL0_RANGE1_SHIFT 8 /**< Current range 1 tuning value for IDAC0 shift */
-#define _DEVINFO_IDAC0CAL0_RANGE2_MASK 0x00FF0000UL /**< Current range 2 tuning value for IDAC0 mask */
-#define _DEVINFO_IDAC0CAL0_RANGE2_SHIFT 16 /**< Current range 2 tuning value for IDAC0 shift */
-#define _DEVINFO_IDAC0CAL0_RANGE3_MASK 0xFF000000UL /**< Current range 3 tuning value for IDAC0 mask */
-#define _DEVINFO_IDAC0CAL0_RANGE3_SHIFT 24 /**< Current range 3 tuning value for IDAC0 shift */
-#define _DEVINFO_AUXHFRCOCAL0_BAND1_MASK 0x000000FFUL /**< 1MHz tuning value for AUXHFRCO, mask */
-#define _DEVINFO_AUXHFRCOCAL0_BAND1_SHIFT 0 /**< 1MHz tuning value for AUXHFRCO, shift */
-#define _DEVINFO_AUXHFRCOCAL0_BAND7_MASK 0x0000FF00UL /**< 7MHz tuning value for AUXHFRCO, mask */
-#define _DEVINFO_AUXHFRCOCAL0_BAND7_SHIFT 8 /**< 7MHz tuning value for AUXHFRCO, shift */
-#define _DEVINFO_AUXHFRCOCAL0_BAND11_MASK 0x00FF0000UL /**< 11MHz tuning value for AUXHFRCO, mask */
-#define _DEVINFO_AUXHFRCOCAL0_BAND11_SHIFT 16 /**< 11MHz tuning value for AUXHFRCO, shift */
-#define _DEVINFO_AUXHFRCOCAL0_BAND14_MASK 0xFF000000UL /**< 14MHz tuning value for AUXHFRCO, mask */
-#define _DEVINFO_AUXHFRCOCAL0_BAND14_SHIFT 24 /**< 14MHz tuning value for AUXHFRCO, shift */
-#define _DEVINFO_AUXHFRCOCAL1_BAND21_MASK 0x000000FFUL /**< 21MHz tuning value for AUXHFRCO, mask */
-#define _DEVINFO_AUXHFRCOCAL1_BAND21_SHIFT 0 /**< 21MHz tuning value for AUXHFRCO, shift */
-#define _DEVINFO_HFRCOCAL0_BAND1_MASK 0x000000FFUL /**< 1MHz tuning value for HFRCO, mask */
-#define _DEVINFO_HFRCOCAL0_BAND1_SHIFT 0 /**< 1MHz tuning value for HFRCO, shift */
-#define _DEVINFO_HFRCOCAL0_BAND7_MASK 0x0000FF00UL /**< 7MHz tuning value for HFRCO, mask */
-#define _DEVINFO_HFRCOCAL0_BAND7_SHIFT 8 /**< 7MHz tuning value for HFRCO, shift */
-#define _DEVINFO_HFRCOCAL0_BAND11_MASK 0x00FF0000UL /**< 11MHz tuning value for HFRCO, mask */
-#define _DEVINFO_HFRCOCAL0_BAND11_SHIFT 16 /**< 11MHz tuning value for HFRCO, shift */
-#define _DEVINFO_HFRCOCAL0_BAND14_MASK 0xFF000000UL /**< 14MHz tuning value for HFRCO, mask */
-#define _DEVINFO_HFRCOCAL0_BAND14_SHIFT 24 /**< 14MHz tuning value for HFRCO, shift */
-#define _DEVINFO_HFRCOCAL1_BAND21_MASK 0x000000FFUL /**< 21MHz tuning value for HFRCO, mask */
-#define _DEVINFO_HFRCOCAL1_BAND21_SHIFT 0 /**< 21MHz tuning value for HFRCO, shift */
-#define _DEVINFO_MEMINFO_FLASH_PAGE_SIZE_MASK 0xFF000000UL /**< Flash page size (refer to ref.man for encoding) mask */
-#define _DEVINFO_MEMINFO_FLASH_PAGE_SIZE_SHIFT 24 /**< Flash page size shift */
-#define _DEVINFO_UNIQUEL_MASK 0xFFFFFFFFUL /**< Lower part of 64-bit device unique number */
-#define _DEVINFO_UNIQUEL_SHIFT 0 /**< Unique Low 32-bit shift */
-#define _DEVINFO_UNIQUEH_MASK 0xFFFFFFFFUL /**< High part of 64-bit device unique number */
-#define _DEVINFO_UNIQUEH_SHIFT 0 /**< Unique High 32-bit shift */
-#define _DEVINFO_MSIZE_SRAM_MASK 0xFFFF0000UL /**< Flash size in kilobytes */
-#define _DEVINFO_MSIZE_SRAM_SHIFT 16 /**< Bit position for flash size */
-#define _DEVINFO_MSIZE_FLASH_MASK 0x0000FFFFUL /**< SRAM size in kilobytes */
-#define _DEVINFO_MSIZE_FLASH_SHIFT 0 /**< Bit position for SRAM size */
-#define _DEVINFO_PART_PROD_REV_MASK 0xFF000000UL /**< Production revision */
-#define _DEVINFO_PART_PROD_REV_SHIFT 24 /**< Bit position for production revision */
-#define _DEVINFO_PART_DEVICE_FAMILY_MASK 0x00FF0000UL /**< Device Family, 0x47 for Gecko */
-#define _DEVINFO_PART_DEVICE_FAMILY_SHIFT 16 /**< Bit position for device family */
-/* Legacy family #defines */
-#define _DEVINFO_PART_DEVICE_FAMILY_G 71 /**< Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_GG 72 /**< Giant Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_TG 73 /**< Tiny Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_LG 74 /**< Leopard Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_WG 75 /**< Wonder Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_ZG 76 /**< Zero Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_HG 77 /**< Happy Gecko Device Family */
-/* New style family #defines */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32G 71 /**< Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32GG 72 /**< Giant Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32TG 73 /**< Tiny Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32LG 74 /**< Leopard Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32WG 75 /**< Wonder Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32ZG 76 /**< Zero Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EFM32HG 77 /**< Happy Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EZR32WG 120 /**< EZR Wonder Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EZR32LG 121 /**< EZR Leopard Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_FAMILY_EZR32HG 122 /**< EZR Happy Gecko Device Family */
-#define _DEVINFO_PART_DEVICE_NUMBER_MASK 0x0000FFFFUL /**< Device number */
-#define _DEVINFO_PART_DEVICE_NUMBER_SHIFT 0 /**< Bit position for device number */
-
-/** @} End of group EFM32ZG_DEVINFO */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma.h
deleted file mode 100644
index 3f9f05818d..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma.h
+++ /dev/null
@@ -1,697 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_DMA register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_DMA
- * @{
- * @brief EFM32ZG_DMA Register Declaration
- ******************************************************************************/
-typedef struct {
- __IM uint32_t STATUS; /**< DMA Status Registers */
- __OM uint32_t CONFIG; /**< DMA Configuration Register */
- __IOM uint32_t CTRLBASE; /**< Channel Control Data Base Pointer Register */
- __IM uint32_t ALTCTRLBASE; /**< Channel Alternate Control Data Base Pointer Register */
- __IM uint32_t CHWAITSTATUS; /**< Channel Wait on Request Status Register */
- __OM uint32_t CHSWREQ; /**< Channel Software Request Register */
- __IOM uint32_t CHUSEBURSTS; /**< Channel Useburst Set Register */
- __OM uint32_t CHUSEBURSTC; /**< Channel Useburst Clear Register */
- __IOM uint32_t CHREQMASKS; /**< Channel Request Mask Set Register */
- __OM uint32_t CHREQMASKC; /**< Channel Request Mask Clear Register */
- __IOM uint32_t CHENS; /**< Channel Enable Set Register */
- __OM uint32_t CHENC; /**< Channel Enable Clear Register */
- __IOM uint32_t CHALTS; /**< Channel Alternate Set Register */
- __OM uint32_t CHALTC; /**< Channel Alternate Clear Register */
- __IOM uint32_t CHPRIS; /**< Channel Priority Set Register */
- __OM uint32_t CHPRIC; /**< Channel Priority Clear Register */
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t ERRORC; /**< Bus Error Clear Register */
-
- uint32_t RESERVED1[880U]; /**< Reserved for future use **/
- __IM uint32_t CHREQSTATUS; /**< Channel Request Status */
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IM uint32_t CHSREQSTATUS; /**< Channel Single Request Status */
-
- uint32_t RESERVED3[121U]; /**< Reserved for future use **/
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable register */
-
- uint32_t RESERVED4[60U]; /**< Reserved registers */
- DMA_CH_TypeDef CH[4U]; /**< Channel registers */
-} DMA_TypeDef; /** DMA Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_DMA_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for DMA STATUS */
-#define _DMA_STATUS_RESETVALUE 0x10030000UL /**< Default value for DMA_STATUS */
-#define _DMA_STATUS_MASK 0x001F00F1UL /**< Mask for DMA_STATUS */
-#define DMA_STATUS_EN (0x1UL << 0) /**< DMA Enable Status */
-#define _DMA_STATUS_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_STATUS_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_STATUS_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_EN_DEFAULT (_DMA_STATUS_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_SHIFT 4 /**< Shift value for DMA_STATE */
-#define _DMA_STATUS_STATE_MASK 0xF0UL /**< Bit mask for DMA_STATE */
-#define _DMA_STATUS_STATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_STATUS */
-#define _DMA_STATUS_STATE_IDLE 0x00000000UL /**< Mode IDLE for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDCHCTRLDATA 0x00000001UL /**< Mode RDCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCENDPTR 0x00000002UL /**< Mode RDSRCENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDDSTENDPTR 0x00000003UL /**< Mode RDDSTENDPTR for DMA_STATUS */
-#define _DMA_STATUS_STATE_RDSRCDATA 0x00000004UL /**< Mode RDSRCDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRDSTDATA 0x00000005UL /**< Mode WRDSTDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_WAITREQCLR 0x00000006UL /**< Mode WAITREQCLR for DMA_STATUS */
-#define _DMA_STATUS_STATE_WRCHCTRLDATA 0x00000007UL /**< Mode WRCHCTRLDATA for DMA_STATUS */
-#define _DMA_STATUS_STATE_STALLED 0x00000008UL /**< Mode STALLED for DMA_STATUS */
-#define _DMA_STATUS_STATE_DONE 0x00000009UL /**< Mode DONE for DMA_STATUS */
-#define _DMA_STATUS_STATE_PERSCATTRANS 0x0000000AUL /**< Mode PERSCATTRANS for DMA_STATUS */
-#define DMA_STATUS_STATE_DEFAULT (_DMA_STATUS_STATE_DEFAULT << 4) /**< Shifted mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_STATE_IDLE (_DMA_STATUS_STATE_IDLE << 4) /**< Shifted mode IDLE for DMA_STATUS */
-#define DMA_STATUS_STATE_RDCHCTRLDATA (_DMA_STATUS_STATE_RDCHCTRLDATA << 4) /**< Shifted mode RDCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCENDPTR (_DMA_STATUS_STATE_RDSRCENDPTR << 4) /**< Shifted mode RDSRCENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDDSTENDPTR (_DMA_STATUS_STATE_RDDSTENDPTR << 4) /**< Shifted mode RDDSTENDPTR for DMA_STATUS */
-#define DMA_STATUS_STATE_RDSRCDATA (_DMA_STATUS_STATE_RDSRCDATA << 4) /**< Shifted mode RDSRCDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WRDSTDATA (_DMA_STATUS_STATE_WRDSTDATA << 4) /**< Shifted mode WRDSTDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_WAITREQCLR (_DMA_STATUS_STATE_WAITREQCLR << 4) /**< Shifted mode WAITREQCLR for DMA_STATUS */
-#define DMA_STATUS_STATE_WRCHCTRLDATA (_DMA_STATUS_STATE_WRCHCTRLDATA << 4) /**< Shifted mode WRCHCTRLDATA for DMA_STATUS */
-#define DMA_STATUS_STATE_STALLED (_DMA_STATUS_STATE_STALLED << 4) /**< Shifted mode STALLED for DMA_STATUS */
-#define DMA_STATUS_STATE_DONE (_DMA_STATUS_STATE_DONE << 4) /**< Shifted mode DONE for DMA_STATUS */
-#define DMA_STATUS_STATE_PERSCATTRANS (_DMA_STATUS_STATE_PERSCATTRANS << 4) /**< Shifted mode PERSCATTRANS for DMA_STATUS */
-#define _DMA_STATUS_CHNUM_SHIFT 16 /**< Shift value for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_MASK 0x1F0000UL /**< Bit mask for DMA_CHNUM */
-#define _DMA_STATUS_CHNUM_DEFAULT 0x00000003UL /**< Mode DEFAULT for DMA_STATUS */
-#define DMA_STATUS_CHNUM_DEFAULT (_DMA_STATUS_CHNUM_DEFAULT << 16) /**< Shifted mode DEFAULT for DMA_STATUS */
-
-/* Bit fields for DMA CONFIG */
-#define _DMA_CONFIG_RESETVALUE 0x00000000UL /**< Default value for DMA_CONFIG */
-#define _DMA_CONFIG_MASK 0x00000021UL /**< Mask for DMA_CONFIG */
-#define DMA_CONFIG_EN (0x1UL << 0) /**< Enable DMA */
-#define _DMA_CONFIG_EN_SHIFT 0 /**< Shift value for DMA_EN */
-#define _DMA_CONFIG_EN_MASK 0x1UL /**< Bit mask for DMA_EN */
-#define _DMA_CONFIG_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_EN_DEFAULT (_DMA_CONFIG_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT (0x1UL << 5) /**< Channel Protection Control */
-#define _DMA_CONFIG_CHPROT_SHIFT 5 /**< Shift value for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_MASK 0x20UL /**< Bit mask for DMA_CHPROT */
-#define _DMA_CONFIG_CHPROT_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CONFIG */
-#define DMA_CONFIG_CHPROT_DEFAULT (_DMA_CONFIG_CHPROT_DEFAULT << 5) /**< Shifted mode DEFAULT for DMA_CONFIG */
-
-/* Bit fields for DMA CTRLBASE */
-#define _DMA_CTRLBASE_RESETVALUE 0x00000000UL /**< Default value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_SHIFT 0 /**< Shift value for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_CTRLBASE */
-#define _DMA_CTRLBASE_CTRLBASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CTRLBASE */
-#define DMA_CTRLBASE_CTRLBASE_DEFAULT (_DMA_CTRLBASE_CTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CTRLBASE */
-
-/* Bit fields for DMA ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_RESETVALUE 0x00000040UL /**< Default value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_SHIFT 0 /**< Shift value for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_MASK 0xFFFFFFFFUL /**< Bit mask for DMA_ALTCTRLBASE */
-#define _DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT 0x00000040UL /**< Mode DEFAULT for DMA_ALTCTRLBASE */
-#define DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT (_DMA_ALTCTRLBASE_ALTCTRLBASE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ALTCTRLBASE */
-
-/* Bit fields for DMA CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_RESETVALUE 0x0000000FUL /**< Default value for DMA_CHWAITSTATUS */
-#define _DMA_CHWAITSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS (0x1UL << 0) /**< Channel 0 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_SHIFT 0 /**< Shift value for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH0WAITSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS (0x1UL << 1) /**< Channel 1 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_SHIFT 1 /**< Shift value for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH1WAITSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS (0x1UL << 2) /**< Channel 2 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_SHIFT 2 /**< Shift value for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH2WAITSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS (0x1UL << 3) /**< Channel 3 Wait on Request Status */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_SHIFT 3 /**< Shift value for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3WAITSTATUS */
-#define _DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT 0x00000001UL /**< Mode DEFAULT for DMA_CHWAITSTATUS */
-#define DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT (_DMA_CHWAITSTATUS_CH3WAITSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHWAITSTATUS */
-
-/* Bit fields for DMA CHSWREQ */
-#define _DMA_CHSWREQ_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSWREQ */
-#define _DMA_CHSWREQ_MASK 0x0000000FUL /**< Mask for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ (0x1UL << 0) /**< Channel 0 Software Request */
-#define _DMA_CHSWREQ_CH0SWREQ_SHIFT 0 /**< Shift value for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_MASK 0x1UL /**< Bit mask for DMA_CH0SWREQ */
-#define _DMA_CHSWREQ_CH0SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH0SWREQ_DEFAULT (_DMA_CHSWREQ_CH0SWREQ_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ (0x1UL << 1) /**< Channel 1 Software Request */
-#define _DMA_CHSWREQ_CH1SWREQ_SHIFT 1 /**< Shift value for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_MASK 0x2UL /**< Bit mask for DMA_CH1SWREQ */
-#define _DMA_CHSWREQ_CH1SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH1SWREQ_DEFAULT (_DMA_CHSWREQ_CH1SWREQ_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ (0x1UL << 2) /**< Channel 2 Software Request */
-#define _DMA_CHSWREQ_CH2SWREQ_SHIFT 2 /**< Shift value for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_MASK 0x4UL /**< Bit mask for DMA_CH2SWREQ */
-#define _DMA_CHSWREQ_CH2SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH2SWREQ_DEFAULT (_DMA_CHSWREQ_CH2SWREQ_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ (0x1UL << 3) /**< Channel 3 Software Request */
-#define _DMA_CHSWREQ_CH3SWREQ_SHIFT 3 /**< Shift value for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_MASK 0x8UL /**< Bit mask for DMA_CH3SWREQ */
-#define _DMA_CHSWREQ_CH3SWREQ_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSWREQ */
-#define DMA_CHSWREQ_CH3SWREQ_DEFAULT (_DMA_CHSWREQ_CH3SWREQ_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSWREQ */
-
-/* Bit fields for DMA CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS (0x1UL << 0) /**< Channel 0 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST 0x00000000UL /**< Mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define _DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY 0x00000001UL /**< Mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH0USEBURSTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST (_DMA_CHUSEBURSTS_CH0USEBURSTS_SINGLEANDBURST << 0) /**< Shifted mode SINGLEANDBURST for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY (_DMA_CHUSEBURSTS_CH0USEBURSTS_BURSTONLY << 0) /**< Shifted mode BURSTONLY for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS (0x1UL << 1) /**< Channel 1 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH1USEBURSTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS (0x1UL << 2) /**< Channel 2 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH2USEBURSTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS (0x1UL << 3) /**< Channel 3 Useburst Set */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTS */
-#define _DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTS */
-#define DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT (_DMA_CHUSEBURSTS_CH3USEBURSTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTS */
-
-/* Bit fields for DMA CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHUSEBURSTC */
-#define _DMA_CHUSEBURSTC_MASK 0x0000000FUL /**< Mask for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC (0x1UL << 0) /**< Channel 0 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_SHIFT 0 /**< Shift value for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_MASK 0x1UL /**< Bit mask for DMA_CH0USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH0USEBURSTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC (0x1UL << 1) /**< Channel 1 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_SHIFT 1 /**< Shift value for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_MASK 0x2UL /**< Bit mask for DMA_CH1USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH1USEBURSTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC (0x1UL << 2) /**< Channel 2 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_SHIFT 2 /**< Shift value for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_MASK 0x4UL /**< Bit mask for DMA_CH2USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH2USEBURSTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC (0x1UL << 3) /**< Channel 3 Useburst Clear */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_SHIFT 3 /**< Shift value for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_MASK 0x8UL /**< Bit mask for DMA_CH3USEBURSTC */
-#define _DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHUSEBURSTC */
-#define DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT (_DMA_CHUSEBURSTC_CH3USEBURSTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHUSEBURSTC */
-
-/* Bit fields for DMA CHREQMASKS */
-#define _DMA_CHREQMASKS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKS */
-#define _DMA_CHREQMASKS_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS (0x1UL << 0) /**< Channel 0 Request Mask Set */
-#define _DMA_CHREQMASKS_CH0REQMASKS_SHIFT 0 /**< Shift value for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKS */
-#define _DMA_CHREQMASKS_CH0REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH0REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH0REQMASKS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS (0x1UL << 1) /**< Channel 1 Request Mask Set */
-#define _DMA_CHREQMASKS_CH1REQMASKS_SHIFT 1 /**< Shift value for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKS */
-#define _DMA_CHREQMASKS_CH1REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH1REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH1REQMASKS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS (0x1UL << 2) /**< Channel 2 Request Mask Set */
-#define _DMA_CHREQMASKS_CH2REQMASKS_SHIFT 2 /**< Shift value for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKS */
-#define _DMA_CHREQMASKS_CH2REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH2REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH2REQMASKS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS (0x1UL << 3) /**< Channel 3 Request Mask Set */
-#define _DMA_CHREQMASKS_CH3REQMASKS_SHIFT 3 /**< Shift value for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKS */
-#define _DMA_CHREQMASKS_CH3REQMASKS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKS */
-#define DMA_CHREQMASKS_CH3REQMASKS_DEFAULT (_DMA_CHREQMASKS_CH3REQMASKS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKS */
-
-/* Bit fields for DMA CHREQMASKC */
-#define _DMA_CHREQMASKC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQMASKC */
-#define _DMA_CHREQMASKC_MASK 0x0000000FUL /**< Mask for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC (0x1UL << 0) /**< Channel 0 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH0REQMASKC_SHIFT 0 /**< Shift value for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_MASK 0x1UL /**< Bit mask for DMA_CH0REQMASKC */
-#define _DMA_CHREQMASKC_CH0REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH0REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH0REQMASKC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC (0x1UL << 1) /**< Channel 1 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH1REQMASKC_SHIFT 1 /**< Shift value for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_MASK 0x2UL /**< Bit mask for DMA_CH1REQMASKC */
-#define _DMA_CHREQMASKC_CH1REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH1REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH1REQMASKC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC (0x1UL << 2) /**< Channel 2 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH2REQMASKC_SHIFT 2 /**< Shift value for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_MASK 0x4UL /**< Bit mask for DMA_CH2REQMASKC */
-#define _DMA_CHREQMASKC_CH2REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH2REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH2REQMASKC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC (0x1UL << 3) /**< Channel 3 Request Mask Clear */
-#define _DMA_CHREQMASKC_CH3REQMASKC_SHIFT 3 /**< Shift value for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_MASK 0x8UL /**< Bit mask for DMA_CH3REQMASKC */
-#define _DMA_CHREQMASKC_CH3REQMASKC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQMASKC */
-#define DMA_CHREQMASKC_CH3REQMASKC_DEFAULT (_DMA_CHREQMASKC_CH3REQMASKC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQMASKC */
-
-/* Bit fields for DMA CHENS */
-#define _DMA_CHENS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENS */
-#define _DMA_CHENS_MASK 0x0000000FUL /**< Mask for DMA_CHENS */
-#define DMA_CHENS_CH0ENS (0x1UL << 0) /**< Channel 0 Enable Set */
-#define _DMA_CHENS_CH0ENS_SHIFT 0 /**< Shift value for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_MASK 0x1UL /**< Bit mask for DMA_CH0ENS */
-#define _DMA_CHENS_CH0ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH0ENS_DEFAULT (_DMA_CHENS_CH0ENS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS (0x1UL << 1) /**< Channel 1 Enable Set */
-#define _DMA_CHENS_CH1ENS_SHIFT 1 /**< Shift value for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_MASK 0x2UL /**< Bit mask for DMA_CH1ENS */
-#define _DMA_CHENS_CH1ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH1ENS_DEFAULT (_DMA_CHENS_CH1ENS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS (0x1UL << 2) /**< Channel 2 Enable Set */
-#define _DMA_CHENS_CH2ENS_SHIFT 2 /**< Shift value for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_MASK 0x4UL /**< Bit mask for DMA_CH2ENS */
-#define _DMA_CHENS_CH2ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH2ENS_DEFAULT (_DMA_CHENS_CH2ENS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS (0x1UL << 3) /**< Channel 3 Enable Set */
-#define _DMA_CHENS_CH3ENS_SHIFT 3 /**< Shift value for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_MASK 0x8UL /**< Bit mask for DMA_CH3ENS */
-#define _DMA_CHENS_CH3ENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENS */
-#define DMA_CHENS_CH3ENS_DEFAULT (_DMA_CHENS_CH3ENS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENS */
-
-/* Bit fields for DMA CHENC */
-#define _DMA_CHENC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHENC */
-#define _DMA_CHENC_MASK 0x0000000FUL /**< Mask for DMA_CHENC */
-#define DMA_CHENC_CH0ENC (0x1UL << 0) /**< Channel 0 Enable Clear */
-#define _DMA_CHENC_CH0ENC_SHIFT 0 /**< Shift value for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_MASK 0x1UL /**< Bit mask for DMA_CH0ENC */
-#define _DMA_CHENC_CH0ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH0ENC_DEFAULT (_DMA_CHENC_CH0ENC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC (0x1UL << 1) /**< Channel 1 Enable Clear */
-#define _DMA_CHENC_CH1ENC_SHIFT 1 /**< Shift value for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_MASK 0x2UL /**< Bit mask for DMA_CH1ENC */
-#define _DMA_CHENC_CH1ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH1ENC_DEFAULT (_DMA_CHENC_CH1ENC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC (0x1UL << 2) /**< Channel 2 Enable Clear */
-#define _DMA_CHENC_CH2ENC_SHIFT 2 /**< Shift value for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_MASK 0x4UL /**< Bit mask for DMA_CH2ENC */
-#define _DMA_CHENC_CH2ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH2ENC_DEFAULT (_DMA_CHENC_CH2ENC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC (0x1UL << 3) /**< Channel 3 Enable Clear */
-#define _DMA_CHENC_CH3ENC_SHIFT 3 /**< Shift value for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_MASK 0x8UL /**< Bit mask for DMA_CH3ENC */
-#define _DMA_CHENC_CH3ENC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHENC */
-#define DMA_CHENC_CH3ENC_DEFAULT (_DMA_CHENC_CH3ENC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHENC */
-
-/* Bit fields for DMA CHALTS */
-#define _DMA_CHALTS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTS */
-#define _DMA_CHALTS_MASK 0x0000000FUL /**< Mask for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS (0x1UL << 0) /**< Channel 0 Alternate Structure Set */
-#define _DMA_CHALTS_CH0ALTS_SHIFT 0 /**< Shift value for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_MASK 0x1UL /**< Bit mask for DMA_CH0ALTS */
-#define _DMA_CHALTS_CH0ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH0ALTS_DEFAULT (_DMA_CHALTS_CH0ALTS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS (0x1UL << 1) /**< Channel 1 Alternate Structure Set */
-#define _DMA_CHALTS_CH1ALTS_SHIFT 1 /**< Shift value for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_MASK 0x2UL /**< Bit mask for DMA_CH1ALTS */
-#define _DMA_CHALTS_CH1ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH1ALTS_DEFAULT (_DMA_CHALTS_CH1ALTS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS (0x1UL << 2) /**< Channel 2 Alternate Structure Set */
-#define _DMA_CHALTS_CH2ALTS_SHIFT 2 /**< Shift value for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_MASK 0x4UL /**< Bit mask for DMA_CH2ALTS */
-#define _DMA_CHALTS_CH2ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH2ALTS_DEFAULT (_DMA_CHALTS_CH2ALTS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS (0x1UL << 3) /**< Channel 3 Alternate Structure Set */
-#define _DMA_CHALTS_CH3ALTS_SHIFT 3 /**< Shift value for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_MASK 0x8UL /**< Bit mask for DMA_CH3ALTS */
-#define _DMA_CHALTS_CH3ALTS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTS */
-#define DMA_CHALTS_CH3ALTS_DEFAULT (_DMA_CHALTS_CH3ALTS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTS */
-
-/* Bit fields for DMA CHALTC */
-#define _DMA_CHALTC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHALTC */
-#define _DMA_CHALTC_MASK 0x0000000FUL /**< Mask for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC (0x1UL << 0) /**< Channel 0 Alternate Clear */
-#define _DMA_CHALTC_CH0ALTC_SHIFT 0 /**< Shift value for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_MASK 0x1UL /**< Bit mask for DMA_CH0ALTC */
-#define _DMA_CHALTC_CH0ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH0ALTC_DEFAULT (_DMA_CHALTC_CH0ALTC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC (0x1UL << 1) /**< Channel 1 Alternate Clear */
-#define _DMA_CHALTC_CH1ALTC_SHIFT 1 /**< Shift value for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_MASK 0x2UL /**< Bit mask for DMA_CH1ALTC */
-#define _DMA_CHALTC_CH1ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH1ALTC_DEFAULT (_DMA_CHALTC_CH1ALTC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC (0x1UL << 2) /**< Channel 2 Alternate Clear */
-#define _DMA_CHALTC_CH2ALTC_SHIFT 2 /**< Shift value for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_MASK 0x4UL /**< Bit mask for DMA_CH2ALTC */
-#define _DMA_CHALTC_CH2ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH2ALTC_DEFAULT (_DMA_CHALTC_CH2ALTC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC (0x1UL << 3) /**< Channel 3 Alternate Clear */
-#define _DMA_CHALTC_CH3ALTC_SHIFT 3 /**< Shift value for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_MASK 0x8UL /**< Bit mask for DMA_CH3ALTC */
-#define _DMA_CHALTC_CH3ALTC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHALTC */
-#define DMA_CHALTC_CH3ALTC_DEFAULT (_DMA_CHALTC_CH3ALTC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHALTC */
-
-/* Bit fields for DMA CHPRIS */
-#define _DMA_CHPRIS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIS */
-#define _DMA_CHPRIS_MASK 0x0000000FUL /**< Mask for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS (0x1UL << 0) /**< Channel 0 High Priority Set */
-#define _DMA_CHPRIS_CH0PRIS_SHIFT 0 /**< Shift value for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_MASK 0x1UL /**< Bit mask for DMA_CH0PRIS */
-#define _DMA_CHPRIS_CH0PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH0PRIS_DEFAULT (_DMA_CHPRIS_CH0PRIS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS (0x1UL << 1) /**< Channel 1 High Priority Set */
-#define _DMA_CHPRIS_CH1PRIS_SHIFT 1 /**< Shift value for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_MASK 0x2UL /**< Bit mask for DMA_CH1PRIS */
-#define _DMA_CHPRIS_CH1PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH1PRIS_DEFAULT (_DMA_CHPRIS_CH1PRIS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS (0x1UL << 2) /**< Channel 2 High Priority Set */
-#define _DMA_CHPRIS_CH2PRIS_SHIFT 2 /**< Shift value for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_MASK 0x4UL /**< Bit mask for DMA_CH2PRIS */
-#define _DMA_CHPRIS_CH2PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH2PRIS_DEFAULT (_DMA_CHPRIS_CH2PRIS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS (0x1UL << 3) /**< Channel 3 High Priority Set */
-#define _DMA_CHPRIS_CH3PRIS_SHIFT 3 /**< Shift value for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_MASK 0x8UL /**< Bit mask for DMA_CH3PRIS */
-#define _DMA_CHPRIS_CH3PRIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIS */
-#define DMA_CHPRIS_CH3PRIS_DEFAULT (_DMA_CHPRIS_CH3PRIS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIS */
-
-/* Bit fields for DMA CHPRIC */
-#define _DMA_CHPRIC_RESETVALUE 0x00000000UL /**< Default value for DMA_CHPRIC */
-#define _DMA_CHPRIC_MASK 0x0000000FUL /**< Mask for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC (0x1UL << 0) /**< Channel 0 High Priority Clear */
-#define _DMA_CHPRIC_CH0PRIC_SHIFT 0 /**< Shift value for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_MASK 0x1UL /**< Bit mask for DMA_CH0PRIC */
-#define _DMA_CHPRIC_CH0PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH0PRIC_DEFAULT (_DMA_CHPRIC_CH0PRIC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC (0x1UL << 1) /**< Channel 1 High Priority Clear */
-#define _DMA_CHPRIC_CH1PRIC_SHIFT 1 /**< Shift value for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_MASK 0x2UL /**< Bit mask for DMA_CH1PRIC */
-#define _DMA_CHPRIC_CH1PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH1PRIC_DEFAULT (_DMA_CHPRIC_CH1PRIC_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC (0x1UL << 2) /**< Channel 2 High Priority Clear */
-#define _DMA_CHPRIC_CH2PRIC_SHIFT 2 /**< Shift value for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_MASK 0x4UL /**< Bit mask for DMA_CH2PRIC */
-#define _DMA_CHPRIC_CH2PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH2PRIC_DEFAULT (_DMA_CHPRIC_CH2PRIC_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC (0x1UL << 3) /**< Channel 3 High Priority Clear */
-#define _DMA_CHPRIC_CH3PRIC_SHIFT 3 /**< Shift value for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_MASK 0x8UL /**< Bit mask for DMA_CH3PRIC */
-#define _DMA_CHPRIC_CH3PRIC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHPRIC */
-#define DMA_CHPRIC_CH3PRIC_DEFAULT (_DMA_CHPRIC_CH3PRIC_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHPRIC */
-
-/* Bit fields for DMA ERRORC */
-#define _DMA_ERRORC_RESETVALUE 0x00000000UL /**< Default value for DMA_ERRORC */
-#define _DMA_ERRORC_MASK 0x00000001UL /**< Mask for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC (0x1UL << 0) /**< Bus Error Clear */
-#define _DMA_ERRORC_ERRORC_SHIFT 0 /**< Shift value for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_MASK 0x1UL /**< Bit mask for DMA_ERRORC */
-#define _DMA_ERRORC_ERRORC_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_ERRORC */
-#define DMA_ERRORC_ERRORC_DEFAULT (_DMA_ERRORC_ERRORC_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_ERRORC */
-
-/* Bit fields for DMA CHREQSTATUS */
-#define _DMA_CHREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHREQSTATUS */
-#define _DMA_CHREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS (0x1UL << 0) /**< Channel 0 Request Status */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0REQSTATUS */
-#define _DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH0REQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS (0x1UL << 1) /**< Channel 1 Request Status */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1REQSTATUS */
-#define _DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH1REQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS (0x1UL << 2) /**< Channel 2 Request Status */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2REQSTATUS */
-#define _DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH2REQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS (0x1UL << 3) /**< Channel 3 Request Status */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3REQSTATUS */
-#define _DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHREQSTATUS */
-#define DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT (_DMA_CHREQSTATUS_CH3REQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHREQSTATUS */
-
-/* Bit fields for DMA CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_RESETVALUE 0x00000000UL /**< Default value for DMA_CHSREQSTATUS */
-#define _DMA_CHSREQSTATUS_MASK 0x0000000FUL /**< Mask for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS (0x1UL << 0) /**< Channel 0 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_SHIFT 0 /**< Shift value for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_MASK 0x1UL /**< Bit mask for DMA_CH0SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH0SREQSTATUS_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS (0x1UL << 1) /**< Channel 1 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_SHIFT 1 /**< Shift value for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_MASK 0x2UL /**< Bit mask for DMA_CH1SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH1SREQSTATUS_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS (0x1UL << 2) /**< Channel 2 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_SHIFT 2 /**< Shift value for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_MASK 0x4UL /**< Bit mask for DMA_CH2SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH2SREQSTATUS_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS (0x1UL << 3) /**< Channel 3 Single Request Status */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_SHIFT 3 /**< Shift value for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_MASK 0x8UL /**< Bit mask for DMA_CH3SREQSTATUS */
-#define _DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_CHSREQSTATUS */
-#define DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT (_DMA_CHSREQSTATUS_CH3SREQSTATUS_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_CHSREQSTATUS */
-
-/* Bit fields for DMA IF */
-#define _DMA_IF_RESETVALUE 0x00000000UL /**< Default value for DMA_IF */
-#define _DMA_IF_MASK 0x8000000FUL /**< Mask for DMA_IF */
-#define DMA_IF_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag */
-#define _DMA_IF_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IF_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH0DONE_DEFAULT (_DMA_IF_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag */
-#define _DMA_IF_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IF_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH1DONE_DEFAULT (_DMA_IF_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag */
-#define _DMA_IF_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IF_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH2DONE_DEFAULT (_DMA_IF_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag */
-#define _DMA_IF_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IF_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_CH3DONE_DEFAULT (_DMA_IF_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag */
-#define _DMA_IF_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IF_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IF_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IF */
-#define DMA_IF_ERR_DEFAULT (_DMA_IF_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IF */
-
-/* Bit fields for DMA IFS */
-#define _DMA_IFS_RESETVALUE 0x00000000UL /**< Default value for DMA_IFS */
-#define _DMA_IFS_MASK 0x8000000FUL /**< Mask for DMA_IFS */
-#define DMA_IFS_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFS_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH0DONE_DEFAULT (_DMA_IFS_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFS_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH1DONE_DEFAULT (_DMA_IFS_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFS_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH2DONE_DEFAULT (_DMA_IFS_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Set */
-#define _DMA_IFS_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFS_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_CH3DONE_DEFAULT (_DMA_IFS_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Set */
-#define _DMA_IFS_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFS_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFS_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFS */
-#define DMA_IFS_ERR_DEFAULT (_DMA_IFS_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFS */
-
-/* Bit fields for DMA IFC */
-#define _DMA_IFC_RESETVALUE 0x00000000UL /**< Default value for DMA_IFC */
-#define _DMA_IFC_MASK 0x8000000FUL /**< Mask for DMA_IFC */
-#define DMA_IFC_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IFC_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH0DONE_DEFAULT (_DMA_IFC_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IFC_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH1DONE_DEFAULT (_DMA_IFC_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IFC_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH2DONE_DEFAULT (_DMA_IFC_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Flag Clear */
-#define _DMA_IFC_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IFC_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_CH3DONE_DEFAULT (_DMA_IFC_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Clear */
-#define _DMA_IFC_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IFC_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IFC_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IFC */
-#define DMA_IFC_ERR_DEFAULT (_DMA_IFC_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IFC */
-
-/* Bit fields for DMA IEN */
-#define _DMA_IEN_RESETVALUE 0x00000000UL /**< Default value for DMA_IEN */
-#define _DMA_IEN_MASK 0x8000000FUL /**< Mask for DMA_IEN */
-#define DMA_IEN_CH0DONE (0x1UL << 0) /**< DMA Channel 0 Complete Interrupt Enable */
-#define _DMA_IEN_CH0DONE_SHIFT 0 /**< Shift value for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_MASK 0x1UL /**< Bit mask for DMA_CH0DONE */
-#define _DMA_IEN_CH0DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH0DONE_DEFAULT (_DMA_IEN_CH0DONE_DEFAULT << 0) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE (0x1UL << 1) /**< DMA Channel 1 Complete Interrupt Enable */
-#define _DMA_IEN_CH1DONE_SHIFT 1 /**< Shift value for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_MASK 0x2UL /**< Bit mask for DMA_CH1DONE */
-#define _DMA_IEN_CH1DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH1DONE_DEFAULT (_DMA_IEN_CH1DONE_DEFAULT << 1) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE (0x1UL << 2) /**< DMA Channel 2 Complete Interrupt Enable */
-#define _DMA_IEN_CH2DONE_SHIFT 2 /**< Shift value for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_MASK 0x4UL /**< Bit mask for DMA_CH2DONE */
-#define _DMA_IEN_CH2DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH2DONE_DEFAULT (_DMA_IEN_CH2DONE_DEFAULT << 2) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE (0x1UL << 3) /**< DMA Channel 3 Complete Interrupt Enable */
-#define _DMA_IEN_CH3DONE_SHIFT 3 /**< Shift value for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_MASK 0x8UL /**< Bit mask for DMA_CH3DONE */
-#define _DMA_IEN_CH3DONE_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_CH3DONE_DEFAULT (_DMA_IEN_CH3DONE_DEFAULT << 3) /**< Shifted mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR (0x1UL << 31) /**< DMA Error Interrupt Flag Enable */
-#define _DMA_IEN_ERR_SHIFT 31 /**< Shift value for DMA_ERR */
-#define _DMA_IEN_ERR_MASK 0x80000000UL /**< Bit mask for DMA_ERR */
-#define _DMA_IEN_ERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for DMA_IEN */
-#define DMA_IEN_ERR_DEFAULT (_DMA_IEN_ERR_DEFAULT << 31) /**< Shifted mode DEFAULT for DMA_IEN */
-
-/* Bit fields for DMA CH_CTRL */
-#define _DMA_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_MASK 0x003F000FUL /**< Mask for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_MASK 0xFUL /**< Bit mask for DMA_SIGSEL */
-#define _DMA_CH_CTRL_SIGSEL_ADC0SINGLE 0x00000000UL /**< Mode ADC0SINGLE for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000000UL /**< Mode USART1RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV 0x00000000UL /**< Mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0RXDATAV 0x00000000UL /**< Mode I2C0RXDATAV for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0UFOF 0x00000000UL /**< Mode TIMER0UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1UFOF 0x00000000UL /**< Mode TIMER1UFOF for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_MSCWDATA 0x00000000UL /**< Mode MSCWDATA for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_AESDATAWR 0x00000000UL /**< Mode AESDATAWR for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_ADC0SCAN 0x00000001UL /**< Mode ADC0SCAN for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBL 0x00000001UL /**< Mode USART1TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXBL 0x00000001UL /**< Mode LEUART0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_I2C0TXBL 0x00000001UL /**< Mode I2C0TXBL for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC0 0x00000001UL /**< Mode TIMER0CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC0 0x00000001UL /**< Mode TIMER1CC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_AESXORDATAWR 0x00000001UL /**< Mode AESXORDATAWR for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXEMPTY 0x00000002UL /**< Mode USART1TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY 0x00000002UL /**< Mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC1 0x00000002UL /**< Mode TIMER0CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC1 0x00000002UL /**< Mode TIMER1CC1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_AESDATARD 0x00000002UL /**< Mode AESDATARD for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT 0x00000003UL /**< Mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER0CC2 0x00000003UL /**< Mode TIMER0CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_TIMER1CC2 0x00000003UL /**< Mode TIMER1CC2 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_AESKEYWR 0x00000003UL /**< Mode AESKEYWR for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT 0x00000004UL /**< Mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_ADC0SINGLE (_DMA_CH_CTRL_SIGSEL_ADC0SINGLE << 0) /**< Shifted mode ADC0SINGLE for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAV (_DMA_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV (_DMA_CH_CTRL_SIGSEL_LEUART0RXDATAV << 0) /**< Shifted mode LEUART0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0RXDATAV (_DMA_CH_CTRL_SIGSEL_I2C0RXDATAV << 0) /**< Shifted mode I2C0RXDATAV for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0UFOF (_DMA_CH_CTRL_SIGSEL_TIMER0UFOF << 0) /**< Shifted mode TIMER0UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1UFOF (_DMA_CH_CTRL_SIGSEL_TIMER1UFOF << 0) /**< Shifted mode TIMER1UFOF for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_MSCWDATA (_DMA_CH_CTRL_SIGSEL_MSCWDATA << 0) /**< Shifted mode MSCWDATA for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_AESDATAWR (_DMA_CH_CTRL_SIGSEL_AESDATAWR << 0) /**< Shifted mode AESDATAWR for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_ADC0SCAN (_DMA_CH_CTRL_SIGSEL_ADC0SCAN << 0) /**< Shifted mode ADC0SCAN for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBL (_DMA_CH_CTRL_SIGSEL_USART1TXBL << 0) /**< Shifted mode USART1TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXBL (_DMA_CH_CTRL_SIGSEL_LEUART0TXBL << 0) /**< Shifted mode LEUART0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_I2C0TXBL (_DMA_CH_CTRL_SIGSEL_I2C0TXBL << 0) /**< Shifted mode I2C0TXBL for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC0 (_DMA_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC0 (_DMA_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_AESXORDATAWR (_DMA_CH_CTRL_SIGSEL_AESXORDATAWR << 0) /**< Shifted mode AESXORDATAWR for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXEMPTY (_DMA_CH_CTRL_SIGSEL_USART1TXEMPTY << 0) /**< Shifted mode USART1TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY (_DMA_CH_CTRL_SIGSEL_LEUART0TXEMPTY << 0) /**< Shifted mode LEUART0TXEMPTY for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC1 (_DMA_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC1 (_DMA_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_AESDATARD (_DMA_CH_CTRL_SIGSEL_AESDATARD << 0) /**< Shifted mode AESDATARD for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT (_DMA_CH_CTRL_SIGSEL_USART1RXDATAVRIGHT << 0) /**< Shifted mode USART1RXDATAVRIGHT for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER0CC2 (_DMA_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_TIMER1CC2 (_DMA_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_AESKEYWR (_DMA_CH_CTRL_SIGSEL_AESKEYWR << 0) /**< Shifted mode AESKEYWR for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT (_DMA_CH_CTRL_SIGSEL_USART1TXBLRIGHT << 0) /**< Shifted mode USART1TXBLRIGHT for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for DMA_SOURCESEL */
-#define _DMA_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_ADC0 0x00000008UL /**< Mode ADC0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_USART1 0x0000000DUL /**< Mode USART1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_LEUART0 0x00000010UL /**< Mode LEUART0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_I2C0 0x00000014UL /**< Mode I2C0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER0 0x00000018UL /**< Mode TIMER0 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_TIMER1 0x00000019UL /**< Mode TIMER1 for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_MSC 0x00000030UL /**< Mode MSC for DMA_CH_CTRL */
-#define _DMA_CH_CTRL_SOURCESEL_AES 0x00000031UL /**< Mode AES for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_NONE (_DMA_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_ADC0 (_DMA_CH_CTRL_SOURCESEL_ADC0 << 16) /**< Shifted mode ADC0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_USART1 (_DMA_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_LEUART0 (_DMA_CH_CTRL_SOURCESEL_LEUART0 << 16) /**< Shifted mode LEUART0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_I2C0 (_DMA_CH_CTRL_SOURCESEL_I2C0 << 16) /**< Shifted mode I2C0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER0 (_DMA_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_TIMER1 (_DMA_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_MSC (_DMA_CH_CTRL_SOURCESEL_MSC << 16) /**< Shifted mode MSC for DMA_CH_CTRL */
-#define DMA_CH_CTRL_SOURCESEL_AES (_DMA_CH_CTRL_SOURCESEL_AES << 16) /**< Shifted mode AES for DMA_CH_CTRL */
-
-/** @} End of group EFM32ZG_DMA */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma_ch.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma_ch.h
deleted file mode 100644
index 511a2e2186..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma_ch.h
+++ /dev/null
@@ -1,48 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_DMA_CH register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @brief DMA_CH EFM32ZG DMA CH
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Channel Control Register */
-} DMA_CH_TypeDef;
-
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma_descriptor.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma_descriptor.h
deleted file mode 100644
index 02dc579cd7..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dma_descriptor.h
+++ /dev/null
@@ -1,54 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_DMA_DESCRIPTOR register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_DMA_DESCRIPTOR
- * @{
- ******************************************************************************/
-typedef struct {
- /* Note! Use of double __IOM (volatile) qualifier to ensure that both */
- /* pointer and referenced memory are declared volatile. */
- __IOM void * __IOM SRCEND; /**< DMA source address end */
- __IOM void * __IOM DSTEND; /**< DMA destination address end */
- __IOM uint32_t CTRL; /**< DMA control register */
- __IOM uint32_t USER; /**< DMA padding register, available for user */
-} DMA_DESCRIPTOR_TypeDef; /** @} */
-
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dmactrl.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dmactrl.h
deleted file mode 100644
index d36783728c..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dmactrl.h
+++ /dev/null
@@ -1,144 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_DMACTRL register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_DMACTRL_BitFields
- * @{
- ******************************************************************************/
-#define _DMA_CTRL_DST_INC_MASK 0xC0000000UL /**< Data increment for destination, bit mask */
-#define _DMA_CTRL_DST_INC_SHIFT 30 /**< Data increment for destination, shift value */
-#define _DMA_CTRL_DST_INC_BYTE 0x00 /**< Byte/8-bit increment */
-#define _DMA_CTRL_DST_INC_HALFWORD 0x01 /**< Half word/16-bit increment */
-#define _DMA_CTRL_DST_INC_WORD 0x02 /**< Word/32-bit increment */
-#define _DMA_CTRL_DST_INC_NONE 0x03 /**< No increment */
-#define DMA_CTRL_DST_INC_BYTE 0x00000000UL /**< Byte/8-bit increment */
-#define DMA_CTRL_DST_INC_HALFWORD 0x40000000UL /**< Half word/16-bit increment */
-#define DMA_CTRL_DST_INC_WORD 0x80000000UL /**< Word/32-bit increment */
-#define DMA_CTRL_DST_INC_NONE 0xC0000000UL /**< No increment */
-#define _DMA_CTRL_DST_SIZE_MASK 0x30000000UL /**< Data size for destination - MUST be the same as source, bit mask */
-#define _DMA_CTRL_DST_SIZE_SHIFT 28 /**< Data size for destination - MUST be the same as source, shift value */
-#define _DMA_CTRL_DST_SIZE_BYTE 0x00 /**< Byte/8-bit data size */
-#define _DMA_CTRL_DST_SIZE_HALFWORD 0x01 /**< Half word/16-bit data size */
-#define _DMA_CTRL_DST_SIZE_WORD 0x02 /**< Word/32-bit data size */
-#define _DMA_CTRL_DST_SIZE_RSVD 0x03 /**< Reserved */
-#define DMA_CTRL_DST_SIZE_BYTE 0x00000000UL /**< Byte/8-bit data size */
-#define DMA_CTRL_DST_SIZE_HALFWORD 0x10000000UL /**< Half word/16-bit data size */
-#define DMA_CTRL_DST_SIZE_WORD 0x20000000UL /**< Word/32-bit data size */
-#define DMA_CTRL_DST_SIZE_RSVD 0x30000000UL /**< Reserved - do not use */
-#define _DMA_CTRL_SRC_INC_MASK 0x0C000000UL /**< Data increment for source, bit mask */
-#define _DMA_CTRL_SRC_INC_SHIFT 26 /**< Data increment for source, shift value */
-#define _DMA_CTRL_SRC_INC_BYTE 0x00 /**< Byte/8-bit increment */
-#define _DMA_CTRL_SRC_INC_HALFWORD 0x01 /**< Half word/16-bit increment */
-#define _DMA_CTRL_SRC_INC_WORD 0x02 /**< Word/32-bit increment */
-#define _DMA_CTRL_SRC_INC_NONE 0x03 /**< No increment */
-#define DMA_CTRL_SRC_INC_BYTE 0x00000000UL /**< Byte/8-bit increment */
-#define DMA_CTRL_SRC_INC_HALFWORD 0x04000000UL /**< Half word/16-bit increment */
-#define DMA_CTRL_SRC_INC_WORD 0x08000000UL /**< Word/32-bit increment */
-#define DMA_CTRL_SRC_INC_NONE 0x0C000000UL /**< No increment */
-#define _DMA_CTRL_SRC_SIZE_MASK 0x03000000UL /**< Data size for source - MUST be the same as destination, bit mask */
-#define _DMA_CTRL_SRC_SIZE_SHIFT 24 /**< Data size for source - MUST be the same as destination, shift value */
-#define _DMA_CTRL_SRC_SIZE_BYTE 0x00 /**< Byte/8-bit data size */
-#define _DMA_CTRL_SRC_SIZE_HALFWORD 0x01 /**< Half word/16-bit data size */
-#define _DMA_CTRL_SRC_SIZE_WORD 0x02 /**< Word/32-bit data size */
-#define _DMA_CTRL_SRC_SIZE_RSVD 0x03 /**< Reserved */
-#define DMA_CTRL_SRC_SIZE_BYTE 0x00000000UL /**< Byte/8-bit data size */
-#define DMA_CTRL_SRC_SIZE_HALFWORD 0x01000000UL /**< Half word/16-bit data size */
-#define DMA_CTRL_SRC_SIZE_WORD 0x02000000UL /**< Word/32-bit data size */
-#define DMA_CTRL_SRC_SIZE_RSVD 0x03000000UL /**< Reserved - do not use */
-#define _DMA_CTRL_DST_PROT_CTRL_MASK 0x00E00000UL /**< Protection flag for destination, bit mask */
-#define _DMA_CTRL_DST_PROT_CTRL_SHIFT 21 /**< Protection flag for destination, shift value */
-#define DMA_CTRL_DST_PROT_PRIVILEGED 0x00200000UL /**< Privileged mode for destination */
-#define DMA_CTRL_DST_PROT_NON_PRIVILEGED 0x00000000UL /**< Non-privileged mode for estination */
-#define _DMA_CTRL_SRC_PROT_CTRL_MASK 0x001C0000UL /**< Protection flag for source, bit mask */
-#define _DMA_CTRL_SRC_PROT_CTRL_SHIFT 18 /**< Protection flag for source, shift value */
-#define DMA_CTRL_SRC_PROT_PRIVILEGED 0x00040000UL /**< Privileged mode for destination */
-#define DMA_CTRL_SRC_PROT_NON_PRIVILEGED 0x00000000UL /**< Non-privileged mode for estination */
-#define _DMA_CTRL_PROT_NON_PRIVILEGED 0x00 /**< Protection bits to indicate non-privileged access */
-#define _DMA_CTRL_PROT_PRIVILEGED 0x01 /**< Protection bits to indicate privileged access */
-#define _DMA_CTRL_R_POWER_MASK 0x0003C000UL /**< DMA arbitration mask */
-#define _DMA_CTRL_R_POWER_SHIFT 14 /**< Number of DMA cycles before controller does new arbitration in 2^R */
-#define _DMA_CTRL_R_POWER_1 0x00 /**< Arbitrate after each transfer */
-#define _DMA_CTRL_R_POWER_2 0x01 /**< Arbitrate after every 2 transfers */
-#define _DMA_CTRL_R_POWER_4 0x02 /**< Arbitrate after every 4 transfers */
-#define _DMA_CTRL_R_POWER_8 0x03 /**< Arbitrate after every 8 transfers */
-#define _DMA_CTRL_R_POWER_16 0x04 /**< Arbitrate after every 16 transfers */
-#define _DMA_CTRL_R_POWER_32 0x05 /**< Arbitrate after every 32 transfers */
-#define _DMA_CTRL_R_POWER_64 0x06 /**< Arbitrate after every 64 transfers */
-#define _DMA_CTRL_R_POWER_128 0x07 /**< Arbitrate after every 128 transfers */
-#define _DMA_CTRL_R_POWER_256 0x08 /**< Arbitrate after every 256 transfers */
-#define _DMA_CTRL_R_POWER_512 0x09 /**< Arbitrate after every 512 transfers */
-#define _DMA_CTRL_R_POWER_1024 0x0a /**< Arbitrate after every 1024 transfers */
-#define DMA_CTRL_R_POWER_1 0x00000000UL /**< Arbitrate after each transfer */
-#define DMA_CTRL_R_POWER_2 0x00004000UL /**< Arbitrate after every 2 transfers */
-#define DMA_CTRL_R_POWER_4 0x00008000UL /**< Arbitrate after every 4 transfers */
-#define DMA_CTRL_R_POWER_8 0x0000c000UL /**< Arbitrate after every 8 transfers */
-#define DMA_CTRL_R_POWER_16 0x00010000UL /**< Arbitrate after every 16 transfers */
-#define DMA_CTRL_R_POWER_32 0x00014000UL /**< Arbitrate after every 32 transfers */
-#define DMA_CTRL_R_POWER_64 0x00018000UL /**< Arbitrate after every 64 transfers */
-#define DMA_CTRL_R_POWER_128 0x0001c000UL /**< Arbitrate after every 128 transfers */
-#define DMA_CTRL_R_POWER_256 0x00020000UL /**< Arbitrate after every 256 transfers */
-#define DMA_CTRL_R_POWER_512 0x00024000UL /**< Arbitrate after every 512 transfers */
-#define DMA_CTRL_R_POWER_1024 0x00028000UL /**< Arbitrate after every 1024 transfers */
-#define _DMA_CTRL_N_MINUS_1_MASK 0x00003FF0UL /**< Number of DMA transfers minus 1, bit mask. See PL230 documentation */
-#define _DMA_CTRL_N_MINUS_1_SHIFT 4 /**< Number of DMA transfers minus 1, shift mask. See PL230 documentation */
-#define _DMA_CTRL_NEXT_USEBURST_MASK 0x00000008UL /**< DMA useburst_set[C] is 1 when using scatter-gather DMA and using alternate data */
-#define _DMA_CTRL_NEXT_USEBURST_SHIFT 3 /**< DMA useburst shift */
-#define _DMA_CTRL_CYCLE_CTRL_MASK 0x00000007UL /**< DMA Cycle control bit mask - basic/auto/ping-poing/scath-gath */
-#define _DMA_CTRL_CYCLE_CTRL_SHIFT 0 /**< DMA Cycle control bit shift */
-#define _DMA_CTRL_CYCLE_CTRL_INVALID 0x00 /**< Invalid cycle type */
-#define _DMA_CTRL_CYCLE_CTRL_BASIC 0x01 /**< Basic cycle type */
-#define _DMA_CTRL_CYCLE_CTRL_AUTO 0x02 /**< Auto cycle type */
-#define _DMA_CTRL_CYCLE_CTRL_PINGPONG 0x03 /**< PingPong cycle type */
-#define _DMA_CTRL_CYCLE_CTRL_MEM_SCATTER_GATHER 0x04 /**< Memory scatter gather cycle type */
-#define _DMA_CTRL_CYCLE_CTRL_MEM_SCATTER_GATHER_ALT 0x05 /**< Memory scatter gather using alternate structure */
-#define _DMA_CTRL_CYCLE_CTRL_PER_SCATTER_GATHER 0x06 /**< Peripheral scatter gather cycle type */
-#define _DMA_CTRL_CYCLE_CTRL_PER_SCATTER_GATHER_ALT 0x07 /**< Peripheral scatter gather cycle type using alternate structure */
-#define DMA_CTRL_CYCLE_CTRL_INVALID 0x00000000UL /**< Invalid cycle type */
-#define DMA_CTRL_CYCLE_CTRL_BASIC 0x00000001UL /**< Basic cycle type */
-#define DMA_CTRL_CYCLE_CTRL_AUTO 0x00000002UL /**< Auto cycle type */
-#define DMA_CTRL_CYCLE_CTRL_PINGPONG 0x00000003UL /**< PingPong cycle type */
-#define DMA_CTRL_CYCLE_CTRL_MEM_SCATTER_GATHER 0x000000004UL /**< Memory scatter gather cycle type */
-#define DMA_CTRL_CYCLE_CTRL_MEM_SCATTER_GATHER_ALT 0x000000005UL /**< Memory scatter gather using alternate structure */
-#define DMA_CTRL_CYCLE_CTRL_PER_SCATTER_GATHER 0x000000006UL /**< Peripheral scatter gather cycle type */
-#define DMA_CTRL_CYCLE_CTRL_PER_SCATTER_GATHER_ALT 0x000000007UL /**< Peripheral scatter gather cycle type using alternate structure */
-
-/** @} End of group EFM32ZG_DMA */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dmareq.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dmareq.h
deleted file mode 100644
index f08bcfaa7c..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_dmareq.h
+++ /dev/null
@@ -1,73 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_DMAREQ register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_DMAREQ_BitFields
- * @{
- ******************************************************************************/
-#define DMAREQ_ADC0_SINGLE ((8 << 16) + 0) /**< DMA channel select for ADC0_SINGLE */
-#define DMAREQ_ADC0_SCAN ((8 << 16) + 1) /**< DMA channel select for ADC0_SCAN */
-#define DMAREQ_USART1_RXDATAV ((13 << 16) + 0) /**< DMA channel select for USART1_RXDATAV */
-#define DMAREQ_USART1_TXBL ((13 << 16) + 1) /**< DMA channel select for USART1_TXBL */
-#define DMAREQ_USART1_TXEMPTY ((13 << 16) + 2) /**< DMA channel select for USART1_TXEMPTY */
-#define DMAREQ_USART1_RXDATAVRIGHT ((13 << 16) + 3) /**< DMA channel select for USART1_RXDATAVRIGHT */
-#define DMAREQ_USART1_TXBLRIGHT ((13 << 16) + 4) /**< DMA channel select for USART1_TXBLRIGHT */
-#define DMAREQ_LEUART0_RXDATAV ((16 << 16) + 0) /**< DMA channel select for LEUART0_RXDATAV */
-#define DMAREQ_LEUART0_TXBL ((16 << 16) + 1) /**< DMA channel select for LEUART0_TXBL */
-#define DMAREQ_LEUART0_TXEMPTY ((16 << 16) + 2) /**< DMA channel select for LEUART0_TXEMPTY */
-#define DMAREQ_I2C0_RXDATAV ((20 << 16) + 0) /**< DMA channel select for I2C0_RXDATAV */
-#define DMAREQ_I2C0_TXBL ((20 << 16) + 1) /**< DMA channel select for I2C0_TXBL */
-#define DMAREQ_TIMER0_UFOF ((24 << 16) + 0) /**< DMA channel select for TIMER0_UFOF */
-#define DMAREQ_TIMER0_CC0 ((24 << 16) + 1) /**< DMA channel select for TIMER0_CC0 */
-#define DMAREQ_TIMER0_CC1 ((24 << 16) + 2) /**< DMA channel select for TIMER0_CC1 */
-#define DMAREQ_TIMER0_CC2 ((24 << 16) + 3) /**< DMA channel select for TIMER0_CC2 */
-#define DMAREQ_TIMER1_UFOF ((25 << 16) + 0) /**< DMA channel select for TIMER1_UFOF */
-#define DMAREQ_TIMER1_CC0 ((25 << 16) + 1) /**< DMA channel select for TIMER1_CC0 */
-#define DMAREQ_TIMER1_CC1 ((25 << 16) + 2) /**< DMA channel select for TIMER1_CC1 */
-#define DMAREQ_TIMER1_CC2 ((25 << 16) + 3) /**< DMA channel select for TIMER1_CC2 */
-#define DMAREQ_MSC_WDATA ((48 << 16) + 0) /**< DMA channel select for MSC_WDATA */
-#define DMAREQ_AES_DATAWR ((49 << 16) + 0) /**< DMA channel select for AES_DATAWR */
-#define DMAREQ_AES_XORDATAWR ((49 << 16) + 1) /**< DMA channel select for AES_XORDATAWR */
-#define DMAREQ_AES_DATARD ((49 << 16) + 2) /**< DMA channel select for AES_DATARD */
-#define DMAREQ_AES_KEYWR ((49 << 16) + 3) /**< DMA channel select for AES_KEYWR */
-
-/** @} End of group EFM32ZG_DMAREQ */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_emu.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_emu.h
deleted file mode 100644
index 922d0aa0e3..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_emu.h
+++ /dev/null
@@ -1,109 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_EMU register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_EMU
- * @{
- * @brief EFM32ZG_EMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved for future use **/
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
-
- uint32_t RESERVED1[6U]; /**< Reserved for future use **/
- __IOM uint32_t AUXCTRL; /**< Auxiliary Control Register */
-} EMU_TypeDef; /** EMU Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_EMU_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for EMU CTRL */
-#define _EMU_CTRL_RESETVALUE 0x00000000UL /**< Default value for EMU_CTRL */
-#define _EMU_CTRL_MASK 0x0000000FUL /**< Mask for EMU_CTRL */
-#define EMU_CTRL_EMVREG (0x1UL << 0) /**< Energy Mode Voltage Regulator Control */
-#define _EMU_CTRL_EMVREG_SHIFT 0 /**< Shift value for EMU_EMVREG */
-#define _EMU_CTRL_EMVREG_MASK 0x1UL /**< Bit mask for EMU_EMVREG */
-#define _EMU_CTRL_EMVREG_DEFAULT 0x00000000UL /**< Mode DEFAULT for EMU_CTRL */
-#define _EMU_CTRL_EMVREG_REDUCED 0x00000000UL /**< Mode REDUCED for EMU_CTRL */
-#define _EMU_CTRL_EMVREG_FULL 0x00000001UL /**< Mode FULL for EMU_CTRL */
-#define EMU_CTRL_EMVREG_DEFAULT (_EMU_CTRL_EMVREG_DEFAULT << 0) /**< Shifted mode DEFAULT for EMU_CTRL */
-#define EMU_CTRL_EMVREG_REDUCED (_EMU_CTRL_EMVREG_REDUCED << 0) /**< Shifted mode REDUCED for EMU_CTRL */
-#define EMU_CTRL_EMVREG_FULL (_EMU_CTRL_EMVREG_FULL << 0) /**< Shifted mode FULL for EMU_CTRL */
-#define EMU_CTRL_EM2BLOCK (0x1UL << 1) /**< Energy Mode 2 Block */
-#define _EMU_CTRL_EM2BLOCK_SHIFT 1 /**< Shift value for EMU_EM2BLOCK */
-#define _EMU_CTRL_EM2BLOCK_MASK 0x2UL /**< Bit mask for EMU_EM2BLOCK */
-#define _EMU_CTRL_EM2BLOCK_DEFAULT 0x00000000UL /**< Mode DEFAULT for EMU_CTRL */
-#define EMU_CTRL_EM2BLOCK_DEFAULT (_EMU_CTRL_EM2BLOCK_DEFAULT << 1) /**< Shifted mode DEFAULT for EMU_CTRL */
-#define _EMU_CTRL_EM4CTRL_SHIFT 2 /**< Shift value for EMU_EM4CTRL */
-#define _EMU_CTRL_EM4CTRL_MASK 0xCUL /**< Bit mask for EMU_EM4CTRL */
-#define _EMU_CTRL_EM4CTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for EMU_CTRL */
-#define EMU_CTRL_EM4CTRL_DEFAULT (_EMU_CTRL_EM4CTRL_DEFAULT << 2) /**< Shifted mode DEFAULT for EMU_CTRL */
-
-/* Bit fields for EMU LOCK */
-#define _EMU_LOCK_RESETVALUE 0x00000000UL /**< Default value for EMU_LOCK */
-#define _EMU_LOCK_MASK 0x0000FFFFUL /**< Mask for EMU_LOCK */
-#define _EMU_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for EMU_LOCKKEY */
-#define _EMU_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for EMU_LOCKKEY */
-#define _EMU_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for EMU_LOCK */
-#define _EMU_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for EMU_LOCK */
-#define _EMU_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for EMU_LOCK */
-#define _EMU_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for EMU_LOCK */
-#define _EMU_LOCK_LOCKKEY_UNLOCK 0x0000ADE8UL /**< Mode UNLOCK for EMU_LOCK */
-#define EMU_LOCK_LOCKKEY_DEFAULT (_EMU_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for EMU_LOCK */
-#define EMU_LOCK_LOCKKEY_LOCK (_EMU_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for EMU_LOCK */
-#define EMU_LOCK_LOCKKEY_UNLOCKED (_EMU_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for EMU_LOCK */
-#define EMU_LOCK_LOCKKEY_LOCKED (_EMU_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for EMU_LOCK */
-#define EMU_LOCK_LOCKKEY_UNLOCK (_EMU_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for EMU_LOCK */
-
-/* Bit fields for EMU AUXCTRL */
-#define _EMU_AUXCTRL_RESETVALUE 0x00000000UL /**< Default value for EMU_AUXCTRL */
-#define _EMU_AUXCTRL_MASK 0x00000001UL /**< Mask for EMU_AUXCTRL */
-#define EMU_AUXCTRL_HRCCLR (0x1UL << 0) /**< Hard Reset Cause Clear */
-#define _EMU_AUXCTRL_HRCCLR_SHIFT 0 /**< Shift value for EMU_HRCCLR */
-#define _EMU_AUXCTRL_HRCCLR_MASK 0x1UL /**< Bit mask for EMU_HRCCLR */
-#define _EMU_AUXCTRL_HRCCLR_DEFAULT 0x00000000UL /**< Mode DEFAULT for EMU_AUXCTRL */
-#define EMU_AUXCTRL_HRCCLR_DEFAULT (_EMU_AUXCTRL_HRCCLR_DEFAULT << 0) /**< Shifted mode DEFAULT for EMU_AUXCTRL */
-
-/** @} End of group EFM32ZG_EMU */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_gpio.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_gpio.h
deleted file mode 100644
index 7f87610022..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_gpio.h
+++ /dev/null
@@ -1,1151 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_GPIO register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_GPIO
- * @{
- * @brief EFM32ZG_GPIO Register Declaration
- ******************************************************************************/
-typedef struct {
- GPIO_P_TypeDef P[6U]; /**< Port configuration bits */
-
- uint32_t RESERVED0[10U]; /**< Reserved for future use **/
- __IOM uint32_t EXTIPSELL; /**< External Interrupt Port Select Low Register */
- __IOM uint32_t EXTIPSELH; /**< External Interrupt Port Select High Register */
- __IOM uint32_t EXTIRISE; /**< External Interrupt Rising Edge Trigger Register */
- __IOM uint32_t EXTIFALL; /**< External Interrupt Falling Edge Trigger Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
-
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t INSENSE; /**< Input Sense Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
- __IOM uint32_t CTRL; /**< GPIO Control Register */
- __IOM uint32_t CMD; /**< GPIO Command Register */
- __IOM uint32_t EM4WUEN; /**< EM4 Wake-up Enable Register */
- __IOM uint32_t EM4WUPOL; /**< EM4 Wake-up Polarity Register */
- __IM uint32_t EM4WUCAUSE; /**< EM4 Wake-up Cause Register */
-} GPIO_TypeDef; /** GPIO Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_GPIO_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for GPIO P_CTRL */
-#define _GPIO_P_CTRL_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_CTRL */
-#define _GPIO_P_CTRL_MASK 0x00000003UL /**< Mask for GPIO_P_CTRL */
-#define _GPIO_P_CTRL_DRIVEMODE_SHIFT 0 /**< Shift value for GPIO_DRIVEMODE */
-#define _GPIO_P_CTRL_DRIVEMODE_MASK 0x3UL /**< Bit mask for GPIO_DRIVEMODE */
-#define _GPIO_P_CTRL_DRIVEMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_CTRL */
-#define _GPIO_P_CTRL_DRIVEMODE_STANDARD 0x00000000UL /**< Mode STANDARD for GPIO_P_CTRL */
-#define _GPIO_P_CTRL_DRIVEMODE_LOWEST 0x00000001UL /**< Mode LOWEST for GPIO_P_CTRL */
-#define _GPIO_P_CTRL_DRIVEMODE_HIGH 0x00000002UL /**< Mode HIGH for GPIO_P_CTRL */
-#define _GPIO_P_CTRL_DRIVEMODE_LOW 0x00000003UL /**< Mode LOW for GPIO_P_CTRL */
-#define GPIO_P_CTRL_DRIVEMODE_DEFAULT (_GPIO_P_CTRL_DRIVEMODE_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_CTRL */
-#define GPIO_P_CTRL_DRIVEMODE_STANDARD (_GPIO_P_CTRL_DRIVEMODE_STANDARD << 0) /**< Shifted mode STANDARD for GPIO_P_CTRL */
-#define GPIO_P_CTRL_DRIVEMODE_LOWEST (_GPIO_P_CTRL_DRIVEMODE_LOWEST << 0) /**< Shifted mode LOWEST for GPIO_P_CTRL */
-#define GPIO_P_CTRL_DRIVEMODE_HIGH (_GPIO_P_CTRL_DRIVEMODE_HIGH << 0) /**< Shifted mode HIGH for GPIO_P_CTRL */
-#define GPIO_P_CTRL_DRIVEMODE_LOW (_GPIO_P_CTRL_DRIVEMODE_LOW << 0) /**< Shifted mode LOW for GPIO_P_CTRL */
-
-/* Bit fields for GPIO P_MODEL */
-#define _GPIO_P_MODEL_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MASK 0xFFFFFFFFUL /**< Mask for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_SHIFT 0 /**< Shift value for GPIO_MODE0 */
-#define _GPIO_P_MODEL_MODE0_MASK 0xFUL /**< Bit mask for GPIO_MODE0 */
-#define _GPIO_P_MODEL_MODE0_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE0_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_DEFAULT (_GPIO_P_MODEL_MODE0_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_DISABLED (_GPIO_P_MODEL_MODE0_DISABLED << 0) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_INPUT (_GPIO_P_MODEL_MODE0_INPUT << 0) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_INPUTPULL (_GPIO_P_MODEL_MODE0_INPUTPULL << 0) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_INPUTPULLFILTER (_GPIO_P_MODEL_MODE0_INPUTPULLFILTER << 0) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_PUSHPULL (_GPIO_P_MODEL_MODE0_PUSHPULL << 0) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE0_PUSHPULLDRIVE << 0) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDOR (_GPIO_P_MODEL_MODE0_WIREDOR << 0) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE0_WIREDORPULLDOWN << 0) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDAND (_GPIO_P_MODEL_MODE0_WIREDAND << 0) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDFILTER (_GPIO_P_MODEL_MODE0_WIREDANDFILTER << 0) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDPULLUP (_GPIO_P_MODEL_MODE0_WIREDANDPULLUP << 0) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE0_WIREDANDPULLUPFILTER << 0) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDDRIVE (_GPIO_P_MODEL_MODE0_WIREDANDDRIVE << 0) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE0_WIREDANDDRIVEFILTER << 0) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE0_WIREDANDDRIVEPULLUP << 0) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE0_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE0_WIREDANDDRIVEPULLUPFILTER << 0) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_SHIFT 4 /**< Shift value for GPIO_MODE1 */
-#define _GPIO_P_MODEL_MODE1_MASK 0xF0UL /**< Bit mask for GPIO_MODE1 */
-#define _GPIO_P_MODEL_MODE1_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE1_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_DEFAULT (_GPIO_P_MODEL_MODE1_DEFAULT << 4) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_DISABLED (_GPIO_P_MODEL_MODE1_DISABLED << 4) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_INPUT (_GPIO_P_MODEL_MODE1_INPUT << 4) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_INPUTPULL (_GPIO_P_MODEL_MODE1_INPUTPULL << 4) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_INPUTPULLFILTER (_GPIO_P_MODEL_MODE1_INPUTPULLFILTER << 4) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_PUSHPULL (_GPIO_P_MODEL_MODE1_PUSHPULL << 4) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE1_PUSHPULLDRIVE << 4) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDOR (_GPIO_P_MODEL_MODE1_WIREDOR << 4) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE1_WIREDORPULLDOWN << 4) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDAND (_GPIO_P_MODEL_MODE1_WIREDAND << 4) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDFILTER (_GPIO_P_MODEL_MODE1_WIREDANDFILTER << 4) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDPULLUP (_GPIO_P_MODEL_MODE1_WIREDANDPULLUP << 4) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE1_WIREDANDPULLUPFILTER << 4) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDDRIVE (_GPIO_P_MODEL_MODE1_WIREDANDDRIVE << 4) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE1_WIREDANDDRIVEFILTER << 4) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE1_WIREDANDDRIVEPULLUP << 4) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE1_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE1_WIREDANDDRIVEPULLUPFILTER << 4) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_SHIFT 8 /**< Shift value for GPIO_MODE2 */
-#define _GPIO_P_MODEL_MODE2_MASK 0xF00UL /**< Bit mask for GPIO_MODE2 */
-#define _GPIO_P_MODEL_MODE2_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE2_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_DEFAULT (_GPIO_P_MODEL_MODE2_DEFAULT << 8) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_DISABLED (_GPIO_P_MODEL_MODE2_DISABLED << 8) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_INPUT (_GPIO_P_MODEL_MODE2_INPUT << 8) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_INPUTPULL (_GPIO_P_MODEL_MODE2_INPUTPULL << 8) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_INPUTPULLFILTER (_GPIO_P_MODEL_MODE2_INPUTPULLFILTER << 8) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_PUSHPULL (_GPIO_P_MODEL_MODE2_PUSHPULL << 8) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE2_PUSHPULLDRIVE << 8) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDOR (_GPIO_P_MODEL_MODE2_WIREDOR << 8) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE2_WIREDORPULLDOWN << 8) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDAND (_GPIO_P_MODEL_MODE2_WIREDAND << 8) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDFILTER (_GPIO_P_MODEL_MODE2_WIREDANDFILTER << 8) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDPULLUP (_GPIO_P_MODEL_MODE2_WIREDANDPULLUP << 8) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE2_WIREDANDPULLUPFILTER << 8) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDDRIVE (_GPIO_P_MODEL_MODE2_WIREDANDDRIVE << 8) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE2_WIREDANDDRIVEFILTER << 8) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE2_WIREDANDDRIVEPULLUP << 8) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE2_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE2_WIREDANDDRIVEPULLUPFILTER << 8) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_SHIFT 12 /**< Shift value for GPIO_MODE3 */
-#define _GPIO_P_MODEL_MODE3_MASK 0xF000UL /**< Bit mask for GPIO_MODE3 */
-#define _GPIO_P_MODEL_MODE3_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE3_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_DEFAULT (_GPIO_P_MODEL_MODE3_DEFAULT << 12) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_DISABLED (_GPIO_P_MODEL_MODE3_DISABLED << 12) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_INPUT (_GPIO_P_MODEL_MODE3_INPUT << 12) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_INPUTPULL (_GPIO_P_MODEL_MODE3_INPUTPULL << 12) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_INPUTPULLFILTER (_GPIO_P_MODEL_MODE3_INPUTPULLFILTER << 12) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_PUSHPULL (_GPIO_P_MODEL_MODE3_PUSHPULL << 12) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE3_PUSHPULLDRIVE << 12) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDOR (_GPIO_P_MODEL_MODE3_WIREDOR << 12) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE3_WIREDORPULLDOWN << 12) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDAND (_GPIO_P_MODEL_MODE3_WIREDAND << 12) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDFILTER (_GPIO_P_MODEL_MODE3_WIREDANDFILTER << 12) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDPULLUP (_GPIO_P_MODEL_MODE3_WIREDANDPULLUP << 12) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE3_WIREDANDPULLUPFILTER << 12) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDDRIVE (_GPIO_P_MODEL_MODE3_WIREDANDDRIVE << 12) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE3_WIREDANDDRIVEFILTER << 12) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE3_WIREDANDDRIVEPULLUP << 12) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE3_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE3_WIREDANDDRIVEPULLUPFILTER << 12) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_SHIFT 16 /**< Shift value for GPIO_MODE4 */
-#define _GPIO_P_MODEL_MODE4_MASK 0xF0000UL /**< Bit mask for GPIO_MODE4 */
-#define _GPIO_P_MODEL_MODE4_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE4_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_DEFAULT (_GPIO_P_MODEL_MODE4_DEFAULT << 16) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_DISABLED (_GPIO_P_MODEL_MODE4_DISABLED << 16) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_INPUT (_GPIO_P_MODEL_MODE4_INPUT << 16) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_INPUTPULL (_GPIO_P_MODEL_MODE4_INPUTPULL << 16) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_INPUTPULLFILTER (_GPIO_P_MODEL_MODE4_INPUTPULLFILTER << 16) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_PUSHPULL (_GPIO_P_MODEL_MODE4_PUSHPULL << 16) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE4_PUSHPULLDRIVE << 16) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDOR (_GPIO_P_MODEL_MODE4_WIREDOR << 16) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE4_WIREDORPULLDOWN << 16) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDAND (_GPIO_P_MODEL_MODE4_WIREDAND << 16) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDFILTER (_GPIO_P_MODEL_MODE4_WIREDANDFILTER << 16) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDPULLUP (_GPIO_P_MODEL_MODE4_WIREDANDPULLUP << 16) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE4_WIREDANDPULLUPFILTER << 16) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDDRIVE (_GPIO_P_MODEL_MODE4_WIREDANDDRIVE << 16) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE4_WIREDANDDRIVEFILTER << 16) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE4_WIREDANDDRIVEPULLUP << 16) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE4_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE4_WIREDANDDRIVEPULLUPFILTER << 16) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_SHIFT 20 /**< Shift value for GPIO_MODE5 */
-#define _GPIO_P_MODEL_MODE5_MASK 0xF00000UL /**< Bit mask for GPIO_MODE5 */
-#define _GPIO_P_MODEL_MODE5_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE5_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_DEFAULT (_GPIO_P_MODEL_MODE5_DEFAULT << 20) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_DISABLED (_GPIO_P_MODEL_MODE5_DISABLED << 20) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_INPUT (_GPIO_P_MODEL_MODE5_INPUT << 20) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_INPUTPULL (_GPIO_P_MODEL_MODE5_INPUTPULL << 20) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_INPUTPULLFILTER (_GPIO_P_MODEL_MODE5_INPUTPULLFILTER << 20) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_PUSHPULL (_GPIO_P_MODEL_MODE5_PUSHPULL << 20) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE5_PUSHPULLDRIVE << 20) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDOR (_GPIO_P_MODEL_MODE5_WIREDOR << 20) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE5_WIREDORPULLDOWN << 20) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDAND (_GPIO_P_MODEL_MODE5_WIREDAND << 20) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDFILTER (_GPIO_P_MODEL_MODE5_WIREDANDFILTER << 20) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDPULLUP (_GPIO_P_MODEL_MODE5_WIREDANDPULLUP << 20) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE5_WIREDANDPULLUPFILTER << 20) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDDRIVE (_GPIO_P_MODEL_MODE5_WIREDANDDRIVE << 20) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE5_WIREDANDDRIVEFILTER << 20) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE5_WIREDANDDRIVEPULLUP << 20) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE5_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE5_WIREDANDDRIVEPULLUPFILTER << 20) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_SHIFT 24 /**< Shift value for GPIO_MODE6 */
-#define _GPIO_P_MODEL_MODE6_MASK 0xF000000UL /**< Bit mask for GPIO_MODE6 */
-#define _GPIO_P_MODEL_MODE6_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE6_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_DEFAULT (_GPIO_P_MODEL_MODE6_DEFAULT << 24) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_DISABLED (_GPIO_P_MODEL_MODE6_DISABLED << 24) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_INPUT (_GPIO_P_MODEL_MODE6_INPUT << 24) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_INPUTPULL (_GPIO_P_MODEL_MODE6_INPUTPULL << 24) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_INPUTPULLFILTER (_GPIO_P_MODEL_MODE6_INPUTPULLFILTER << 24) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_PUSHPULL (_GPIO_P_MODEL_MODE6_PUSHPULL << 24) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE6_PUSHPULLDRIVE << 24) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDOR (_GPIO_P_MODEL_MODE6_WIREDOR << 24) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE6_WIREDORPULLDOWN << 24) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDAND (_GPIO_P_MODEL_MODE6_WIREDAND << 24) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDFILTER (_GPIO_P_MODEL_MODE6_WIREDANDFILTER << 24) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDPULLUP (_GPIO_P_MODEL_MODE6_WIREDANDPULLUP << 24) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE6_WIREDANDPULLUPFILTER << 24) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDDRIVE (_GPIO_P_MODEL_MODE6_WIREDANDDRIVE << 24) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE6_WIREDANDDRIVEFILTER << 24) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE6_WIREDANDDRIVEPULLUP << 24) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE6_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE6_WIREDANDDRIVEPULLUPFILTER << 24) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_SHIFT 28 /**< Shift value for GPIO_MODE7 */
-#define _GPIO_P_MODEL_MODE7_MASK 0xF0000000UL /**< Bit mask for GPIO_MODE7 */
-#define _GPIO_P_MODEL_MODE7_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define _GPIO_P_MODEL_MODE7_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_DEFAULT (_GPIO_P_MODEL_MODE7_DEFAULT << 28) /**< Shifted mode DEFAULT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_DISABLED (_GPIO_P_MODEL_MODE7_DISABLED << 28) /**< Shifted mode DISABLED for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_INPUT (_GPIO_P_MODEL_MODE7_INPUT << 28) /**< Shifted mode INPUT for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_INPUTPULL (_GPIO_P_MODEL_MODE7_INPUTPULL << 28) /**< Shifted mode INPUTPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_INPUTPULLFILTER (_GPIO_P_MODEL_MODE7_INPUTPULLFILTER << 28) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_PUSHPULL (_GPIO_P_MODEL_MODE7_PUSHPULL << 28) /**< Shifted mode PUSHPULL for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_PUSHPULLDRIVE (_GPIO_P_MODEL_MODE7_PUSHPULLDRIVE << 28) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDOR (_GPIO_P_MODEL_MODE7_WIREDOR << 28) /**< Shifted mode WIREDOR for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDORPULLDOWN (_GPIO_P_MODEL_MODE7_WIREDORPULLDOWN << 28) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDAND (_GPIO_P_MODEL_MODE7_WIREDAND << 28) /**< Shifted mode WIREDAND for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDFILTER (_GPIO_P_MODEL_MODE7_WIREDANDFILTER << 28) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDPULLUP (_GPIO_P_MODEL_MODE7_WIREDANDPULLUP << 28) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDPULLUPFILTER (_GPIO_P_MODEL_MODE7_WIREDANDPULLUPFILTER << 28) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDDRIVE (_GPIO_P_MODEL_MODE7_WIREDANDDRIVE << 28) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDDRIVEFILTER (_GPIO_P_MODEL_MODE7_WIREDANDDRIVEFILTER << 28) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDDRIVEPULLUP (_GPIO_P_MODEL_MODE7_WIREDANDDRIVEPULLUP << 28) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEL */
-#define GPIO_P_MODEL_MODE7_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEL_MODE7_WIREDANDDRIVEPULLUPFILTER << 28) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEL */
-
-/* Bit fields for GPIO P_MODEH */
-#define _GPIO_P_MODEH_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MASK 0xFFFFFFFFUL /**< Mask for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_SHIFT 0 /**< Shift value for GPIO_MODE8 */
-#define _GPIO_P_MODEH_MODE8_MASK 0xFUL /**< Bit mask for GPIO_MODE8 */
-#define _GPIO_P_MODEH_MODE8_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE8_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_DEFAULT (_GPIO_P_MODEH_MODE8_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_DISABLED (_GPIO_P_MODEH_MODE8_DISABLED << 0) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_INPUT (_GPIO_P_MODEH_MODE8_INPUT << 0) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_INPUTPULL (_GPIO_P_MODEH_MODE8_INPUTPULL << 0) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_INPUTPULLFILTER (_GPIO_P_MODEH_MODE8_INPUTPULLFILTER << 0) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_PUSHPULL (_GPIO_P_MODEH_MODE8_PUSHPULL << 0) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE8_PUSHPULLDRIVE << 0) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDOR (_GPIO_P_MODEH_MODE8_WIREDOR << 0) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE8_WIREDORPULLDOWN << 0) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDAND (_GPIO_P_MODEH_MODE8_WIREDAND << 0) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDFILTER (_GPIO_P_MODEH_MODE8_WIREDANDFILTER << 0) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDPULLUP (_GPIO_P_MODEH_MODE8_WIREDANDPULLUP << 0) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE8_WIREDANDPULLUPFILTER << 0) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDDRIVE (_GPIO_P_MODEH_MODE8_WIREDANDDRIVE << 0) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE8_WIREDANDDRIVEFILTER << 0) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE8_WIREDANDDRIVEPULLUP << 0) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE8_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE8_WIREDANDDRIVEPULLUPFILTER << 0) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_SHIFT 4 /**< Shift value for GPIO_MODE9 */
-#define _GPIO_P_MODEH_MODE9_MASK 0xF0UL /**< Bit mask for GPIO_MODE9 */
-#define _GPIO_P_MODEH_MODE9_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE9_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_DEFAULT (_GPIO_P_MODEH_MODE9_DEFAULT << 4) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_DISABLED (_GPIO_P_MODEH_MODE9_DISABLED << 4) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_INPUT (_GPIO_P_MODEH_MODE9_INPUT << 4) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_INPUTPULL (_GPIO_P_MODEH_MODE9_INPUTPULL << 4) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_INPUTPULLFILTER (_GPIO_P_MODEH_MODE9_INPUTPULLFILTER << 4) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_PUSHPULL (_GPIO_P_MODEH_MODE9_PUSHPULL << 4) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE9_PUSHPULLDRIVE << 4) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDOR (_GPIO_P_MODEH_MODE9_WIREDOR << 4) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE9_WIREDORPULLDOWN << 4) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDAND (_GPIO_P_MODEH_MODE9_WIREDAND << 4) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDFILTER (_GPIO_P_MODEH_MODE9_WIREDANDFILTER << 4) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDPULLUP (_GPIO_P_MODEH_MODE9_WIREDANDPULLUP << 4) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE9_WIREDANDPULLUPFILTER << 4) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDDRIVE (_GPIO_P_MODEH_MODE9_WIREDANDDRIVE << 4) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE9_WIREDANDDRIVEFILTER << 4) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE9_WIREDANDDRIVEPULLUP << 4) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE9_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE9_WIREDANDDRIVEPULLUPFILTER << 4) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_SHIFT 8 /**< Shift value for GPIO_MODE10 */
-#define _GPIO_P_MODEH_MODE10_MASK 0xF00UL /**< Bit mask for GPIO_MODE10 */
-#define _GPIO_P_MODEH_MODE10_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE10_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_DEFAULT (_GPIO_P_MODEH_MODE10_DEFAULT << 8) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_DISABLED (_GPIO_P_MODEH_MODE10_DISABLED << 8) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_INPUT (_GPIO_P_MODEH_MODE10_INPUT << 8) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_INPUTPULL (_GPIO_P_MODEH_MODE10_INPUTPULL << 8) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_INPUTPULLFILTER (_GPIO_P_MODEH_MODE10_INPUTPULLFILTER << 8) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_PUSHPULL (_GPIO_P_MODEH_MODE10_PUSHPULL << 8) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE10_PUSHPULLDRIVE << 8) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDOR (_GPIO_P_MODEH_MODE10_WIREDOR << 8) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE10_WIREDORPULLDOWN << 8) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDAND (_GPIO_P_MODEH_MODE10_WIREDAND << 8) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDFILTER (_GPIO_P_MODEH_MODE10_WIREDANDFILTER << 8) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDPULLUP (_GPIO_P_MODEH_MODE10_WIREDANDPULLUP << 8) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE10_WIREDANDPULLUPFILTER << 8) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDDRIVE (_GPIO_P_MODEH_MODE10_WIREDANDDRIVE << 8) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE10_WIREDANDDRIVEFILTER << 8) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE10_WIREDANDDRIVEPULLUP << 8) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE10_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE10_WIREDANDDRIVEPULLUPFILTER << 8) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_SHIFT 12 /**< Shift value for GPIO_MODE11 */
-#define _GPIO_P_MODEH_MODE11_MASK 0xF000UL /**< Bit mask for GPIO_MODE11 */
-#define _GPIO_P_MODEH_MODE11_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE11_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_DEFAULT (_GPIO_P_MODEH_MODE11_DEFAULT << 12) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_DISABLED (_GPIO_P_MODEH_MODE11_DISABLED << 12) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_INPUT (_GPIO_P_MODEH_MODE11_INPUT << 12) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_INPUTPULL (_GPIO_P_MODEH_MODE11_INPUTPULL << 12) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_INPUTPULLFILTER (_GPIO_P_MODEH_MODE11_INPUTPULLFILTER << 12) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_PUSHPULL (_GPIO_P_MODEH_MODE11_PUSHPULL << 12) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE11_PUSHPULLDRIVE << 12) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDOR (_GPIO_P_MODEH_MODE11_WIREDOR << 12) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE11_WIREDORPULLDOWN << 12) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDAND (_GPIO_P_MODEH_MODE11_WIREDAND << 12) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDFILTER (_GPIO_P_MODEH_MODE11_WIREDANDFILTER << 12) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDPULLUP (_GPIO_P_MODEH_MODE11_WIREDANDPULLUP << 12) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE11_WIREDANDPULLUPFILTER << 12) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDDRIVE (_GPIO_P_MODEH_MODE11_WIREDANDDRIVE << 12) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE11_WIREDANDDRIVEFILTER << 12) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE11_WIREDANDDRIVEPULLUP << 12) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE11_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE11_WIREDANDDRIVEPULLUPFILTER << 12) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_SHIFT 16 /**< Shift value for GPIO_MODE12 */
-#define _GPIO_P_MODEH_MODE12_MASK 0xF0000UL /**< Bit mask for GPIO_MODE12 */
-#define _GPIO_P_MODEH_MODE12_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE12_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_DEFAULT (_GPIO_P_MODEH_MODE12_DEFAULT << 16) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_DISABLED (_GPIO_P_MODEH_MODE12_DISABLED << 16) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_INPUT (_GPIO_P_MODEH_MODE12_INPUT << 16) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_INPUTPULL (_GPIO_P_MODEH_MODE12_INPUTPULL << 16) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_INPUTPULLFILTER (_GPIO_P_MODEH_MODE12_INPUTPULLFILTER << 16) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_PUSHPULL (_GPIO_P_MODEH_MODE12_PUSHPULL << 16) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE12_PUSHPULLDRIVE << 16) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDOR (_GPIO_P_MODEH_MODE12_WIREDOR << 16) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE12_WIREDORPULLDOWN << 16) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDAND (_GPIO_P_MODEH_MODE12_WIREDAND << 16) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDFILTER (_GPIO_P_MODEH_MODE12_WIREDANDFILTER << 16) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDPULLUP (_GPIO_P_MODEH_MODE12_WIREDANDPULLUP << 16) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE12_WIREDANDPULLUPFILTER << 16) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDDRIVE (_GPIO_P_MODEH_MODE12_WIREDANDDRIVE << 16) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE12_WIREDANDDRIVEFILTER << 16) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE12_WIREDANDDRIVEPULLUP << 16) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE12_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE12_WIREDANDDRIVEPULLUPFILTER << 16) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_SHIFT 20 /**< Shift value for GPIO_MODE13 */
-#define _GPIO_P_MODEH_MODE13_MASK 0xF00000UL /**< Bit mask for GPIO_MODE13 */
-#define _GPIO_P_MODEH_MODE13_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE13_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_DEFAULT (_GPIO_P_MODEH_MODE13_DEFAULT << 20) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_DISABLED (_GPIO_P_MODEH_MODE13_DISABLED << 20) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_INPUT (_GPIO_P_MODEH_MODE13_INPUT << 20) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_INPUTPULL (_GPIO_P_MODEH_MODE13_INPUTPULL << 20) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_INPUTPULLFILTER (_GPIO_P_MODEH_MODE13_INPUTPULLFILTER << 20) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_PUSHPULL (_GPIO_P_MODEH_MODE13_PUSHPULL << 20) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE13_PUSHPULLDRIVE << 20) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDOR (_GPIO_P_MODEH_MODE13_WIREDOR << 20) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE13_WIREDORPULLDOWN << 20) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDAND (_GPIO_P_MODEH_MODE13_WIREDAND << 20) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDFILTER (_GPIO_P_MODEH_MODE13_WIREDANDFILTER << 20) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDPULLUP (_GPIO_P_MODEH_MODE13_WIREDANDPULLUP << 20) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE13_WIREDANDPULLUPFILTER << 20) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDDRIVE (_GPIO_P_MODEH_MODE13_WIREDANDDRIVE << 20) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE13_WIREDANDDRIVEFILTER << 20) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE13_WIREDANDDRIVEPULLUP << 20) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE13_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE13_WIREDANDDRIVEPULLUPFILTER << 20) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_SHIFT 24 /**< Shift value for GPIO_MODE14 */
-#define _GPIO_P_MODEH_MODE14_MASK 0xF000000UL /**< Bit mask for GPIO_MODE14 */
-#define _GPIO_P_MODEH_MODE14_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE14_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_DEFAULT (_GPIO_P_MODEH_MODE14_DEFAULT << 24) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_DISABLED (_GPIO_P_MODEH_MODE14_DISABLED << 24) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_INPUT (_GPIO_P_MODEH_MODE14_INPUT << 24) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_INPUTPULL (_GPIO_P_MODEH_MODE14_INPUTPULL << 24) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_INPUTPULLFILTER (_GPIO_P_MODEH_MODE14_INPUTPULLFILTER << 24) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_PUSHPULL (_GPIO_P_MODEH_MODE14_PUSHPULL << 24) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE14_PUSHPULLDRIVE << 24) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDOR (_GPIO_P_MODEH_MODE14_WIREDOR << 24) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE14_WIREDORPULLDOWN << 24) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDAND (_GPIO_P_MODEH_MODE14_WIREDAND << 24) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDFILTER (_GPIO_P_MODEH_MODE14_WIREDANDFILTER << 24) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDPULLUP (_GPIO_P_MODEH_MODE14_WIREDANDPULLUP << 24) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE14_WIREDANDPULLUPFILTER << 24) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDDRIVE (_GPIO_P_MODEH_MODE14_WIREDANDDRIVE << 24) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE14_WIREDANDDRIVEFILTER << 24) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE14_WIREDANDDRIVEPULLUP << 24) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE14_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE14_WIREDANDDRIVEPULLUPFILTER << 24) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_SHIFT 28 /**< Shift value for GPIO_MODE15 */
-#define _GPIO_P_MODEH_MODE15_MASK 0xF0000000UL /**< Bit mask for GPIO_MODE15 */
-#define _GPIO_P_MODEH_MODE15_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_DISABLED 0x00000000UL /**< Mode DISABLED for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_INPUT 0x00000001UL /**< Mode INPUT for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_INPUTPULL 0x00000002UL /**< Mode INPUTPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_INPUTPULLFILTER 0x00000003UL /**< Mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_PUSHPULL 0x00000004UL /**< Mode PUSHPULL for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_PUSHPULLDRIVE 0x00000005UL /**< Mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDOR 0x00000006UL /**< Mode WIREDOR for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDORPULLDOWN 0x00000007UL /**< Mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDAND 0x00000008UL /**< Mode WIREDAND for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDFILTER 0x00000009UL /**< Mode WIREDANDFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDPULLUP 0x0000000AUL /**< Mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDPULLUPFILTER 0x0000000BUL /**< Mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDDRIVE 0x0000000CUL /**< Mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDDRIVEFILTER 0x0000000DUL /**< Mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDDRIVEPULLUP 0x0000000EUL /**< Mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define _GPIO_P_MODEH_MODE15_WIREDANDDRIVEPULLUPFILTER 0x0000000FUL /**< Mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_DEFAULT (_GPIO_P_MODEH_MODE15_DEFAULT << 28) /**< Shifted mode DEFAULT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_DISABLED (_GPIO_P_MODEH_MODE15_DISABLED << 28) /**< Shifted mode DISABLED for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_INPUT (_GPIO_P_MODEH_MODE15_INPUT << 28) /**< Shifted mode INPUT for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_INPUTPULL (_GPIO_P_MODEH_MODE15_INPUTPULL << 28) /**< Shifted mode INPUTPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_INPUTPULLFILTER (_GPIO_P_MODEH_MODE15_INPUTPULLFILTER << 28) /**< Shifted mode INPUTPULLFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_PUSHPULL (_GPIO_P_MODEH_MODE15_PUSHPULL << 28) /**< Shifted mode PUSHPULL for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_PUSHPULLDRIVE (_GPIO_P_MODEH_MODE15_PUSHPULLDRIVE << 28) /**< Shifted mode PUSHPULLDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDOR (_GPIO_P_MODEH_MODE15_WIREDOR << 28) /**< Shifted mode WIREDOR for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDORPULLDOWN (_GPIO_P_MODEH_MODE15_WIREDORPULLDOWN << 28) /**< Shifted mode WIREDORPULLDOWN for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDAND (_GPIO_P_MODEH_MODE15_WIREDAND << 28) /**< Shifted mode WIREDAND for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDFILTER (_GPIO_P_MODEH_MODE15_WIREDANDFILTER << 28) /**< Shifted mode WIREDANDFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDPULLUP (_GPIO_P_MODEH_MODE15_WIREDANDPULLUP << 28) /**< Shifted mode WIREDANDPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDPULLUPFILTER (_GPIO_P_MODEH_MODE15_WIREDANDPULLUPFILTER << 28) /**< Shifted mode WIREDANDPULLUPFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDDRIVE (_GPIO_P_MODEH_MODE15_WIREDANDDRIVE << 28) /**< Shifted mode WIREDANDDRIVE for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDDRIVEFILTER (_GPIO_P_MODEH_MODE15_WIREDANDDRIVEFILTER << 28) /**< Shifted mode WIREDANDDRIVEFILTER for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDDRIVEPULLUP (_GPIO_P_MODEH_MODE15_WIREDANDDRIVEPULLUP << 28) /**< Shifted mode WIREDANDDRIVEPULLUP for GPIO_P_MODEH */
-#define GPIO_P_MODEH_MODE15_WIREDANDDRIVEPULLUPFILTER (_GPIO_P_MODEH_MODE15_WIREDANDDRIVEPULLUPFILTER << 28) /**< Shifted mode WIREDANDDRIVEPULLUPFILTER for GPIO_P_MODEH */
-
-/* Bit fields for GPIO P_DOUT */
-#define _GPIO_P_DOUT_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_DOUT */
-#define _GPIO_P_DOUT_MASK 0x0000FFFFUL /**< Mask for GPIO_P_DOUT */
-#define _GPIO_P_DOUT_DOUT_SHIFT 0 /**< Shift value for GPIO_DOUT */
-#define _GPIO_P_DOUT_DOUT_MASK 0xFFFFUL /**< Bit mask for GPIO_DOUT */
-#define _GPIO_P_DOUT_DOUT_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_DOUT */
-#define GPIO_P_DOUT_DOUT_DEFAULT (_GPIO_P_DOUT_DOUT_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_DOUT */
-
-/* Bit fields for GPIO P_DOUTSET */
-#define _GPIO_P_DOUTSET_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_DOUTSET */
-#define _GPIO_P_DOUTSET_MASK 0x0000FFFFUL /**< Mask for GPIO_P_DOUTSET */
-#define _GPIO_P_DOUTSET_DOUTSET_SHIFT 0 /**< Shift value for GPIO_DOUTSET */
-#define _GPIO_P_DOUTSET_DOUTSET_MASK 0xFFFFUL /**< Bit mask for GPIO_DOUTSET */
-#define _GPIO_P_DOUTSET_DOUTSET_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_DOUTSET */
-#define GPIO_P_DOUTSET_DOUTSET_DEFAULT (_GPIO_P_DOUTSET_DOUTSET_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_DOUTSET */
-
-/* Bit fields for GPIO P_DOUTCLR */
-#define _GPIO_P_DOUTCLR_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_DOUTCLR */
-#define _GPIO_P_DOUTCLR_MASK 0x0000FFFFUL /**< Mask for GPIO_P_DOUTCLR */
-#define _GPIO_P_DOUTCLR_DOUTCLR_SHIFT 0 /**< Shift value for GPIO_DOUTCLR */
-#define _GPIO_P_DOUTCLR_DOUTCLR_MASK 0xFFFFUL /**< Bit mask for GPIO_DOUTCLR */
-#define _GPIO_P_DOUTCLR_DOUTCLR_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_DOUTCLR */
-#define GPIO_P_DOUTCLR_DOUTCLR_DEFAULT (_GPIO_P_DOUTCLR_DOUTCLR_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_DOUTCLR */
-
-/* Bit fields for GPIO P_DOUTTGL */
-#define _GPIO_P_DOUTTGL_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_DOUTTGL */
-#define _GPIO_P_DOUTTGL_MASK 0x0000FFFFUL /**< Mask for GPIO_P_DOUTTGL */
-#define _GPIO_P_DOUTTGL_DOUTTGL_SHIFT 0 /**< Shift value for GPIO_DOUTTGL */
-#define _GPIO_P_DOUTTGL_DOUTTGL_MASK 0xFFFFUL /**< Bit mask for GPIO_DOUTTGL */
-#define _GPIO_P_DOUTTGL_DOUTTGL_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_DOUTTGL */
-#define GPIO_P_DOUTTGL_DOUTTGL_DEFAULT (_GPIO_P_DOUTTGL_DOUTTGL_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_DOUTTGL */
-
-/* Bit fields for GPIO P_DIN */
-#define _GPIO_P_DIN_RESETVALUE 0x00000000UL /**< Default value for GPIO_P_DIN */
-#define _GPIO_P_DIN_MASK 0x0000FFFFUL /**< Mask for GPIO_P_DIN */
-#define _GPIO_P_DIN_DIN_SHIFT 0 /**< Shift value for GPIO_DIN */
-#define _GPIO_P_DIN_DIN_MASK 0xFFFFUL /**< Bit mask for GPIO_DIN */
-#define _GPIO_P_DIN_DIN_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_P_DIN */
-#define GPIO_P_DIN_DIN_DEFAULT (_GPIO_P_DIN_DIN_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_DIN */
-
-/* Bit fields for GPIO P_PINLOCKN */
-#define _GPIO_P_PINLOCKN_RESETVALUE 0x0000FFFFUL /**< Default value for GPIO_P_PINLOCKN */
-#define _GPIO_P_PINLOCKN_MASK 0x0000FFFFUL /**< Mask for GPIO_P_PINLOCKN */
-#define _GPIO_P_PINLOCKN_PINLOCKN_SHIFT 0 /**< Shift value for GPIO_PINLOCKN */
-#define _GPIO_P_PINLOCKN_PINLOCKN_MASK 0xFFFFUL /**< Bit mask for GPIO_PINLOCKN */
-#define _GPIO_P_PINLOCKN_PINLOCKN_DEFAULT 0x0000FFFFUL /**< Mode DEFAULT for GPIO_P_PINLOCKN */
-#define GPIO_P_PINLOCKN_PINLOCKN_DEFAULT (_GPIO_P_PINLOCKN_PINLOCKN_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_P_PINLOCKN */
-
-/* Bit fields for GPIO EXTIPSELL */
-#define _GPIO_EXTIPSELL_RESETVALUE 0x00000000UL /**< Default value for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_MASK 0x77777777UL /**< Mask for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_SHIFT 0 /**< Shift value for GPIO_EXTIPSEL0 */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_MASK 0x7UL /**< Bit mask for GPIO_EXTIPSEL0 */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL0_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL0_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_PORTA (_GPIO_EXTIPSELL_EXTIPSEL0_PORTA << 0) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_PORTB (_GPIO_EXTIPSELL_EXTIPSEL0_PORTB << 0) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_PORTC (_GPIO_EXTIPSELL_EXTIPSEL0_PORTC << 0) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_PORTD (_GPIO_EXTIPSELL_EXTIPSEL0_PORTD << 0) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_PORTE (_GPIO_EXTIPSELL_EXTIPSEL0_PORTE << 0) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL0_PORTF (_GPIO_EXTIPSELL_EXTIPSEL0_PORTF << 0) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_SHIFT 4 /**< Shift value for GPIO_EXTIPSEL1 */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_MASK 0x70UL /**< Bit mask for GPIO_EXTIPSEL1 */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL1_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL1_DEFAULT << 4) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_PORTA (_GPIO_EXTIPSELL_EXTIPSEL1_PORTA << 4) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_PORTB (_GPIO_EXTIPSELL_EXTIPSEL1_PORTB << 4) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_PORTC (_GPIO_EXTIPSELL_EXTIPSEL1_PORTC << 4) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_PORTD (_GPIO_EXTIPSELL_EXTIPSEL1_PORTD << 4) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_PORTE (_GPIO_EXTIPSELL_EXTIPSEL1_PORTE << 4) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL1_PORTF (_GPIO_EXTIPSELL_EXTIPSEL1_PORTF << 4) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_SHIFT 8 /**< Shift value for GPIO_EXTIPSEL2 */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_MASK 0x700UL /**< Bit mask for GPIO_EXTIPSEL2 */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL2_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL2_DEFAULT << 8) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_PORTA (_GPIO_EXTIPSELL_EXTIPSEL2_PORTA << 8) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_PORTB (_GPIO_EXTIPSELL_EXTIPSEL2_PORTB << 8) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_PORTC (_GPIO_EXTIPSELL_EXTIPSEL2_PORTC << 8) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_PORTD (_GPIO_EXTIPSELL_EXTIPSEL2_PORTD << 8) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_PORTE (_GPIO_EXTIPSELL_EXTIPSEL2_PORTE << 8) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL2_PORTF (_GPIO_EXTIPSELL_EXTIPSEL2_PORTF << 8) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_SHIFT 12 /**< Shift value for GPIO_EXTIPSEL3 */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_MASK 0x7000UL /**< Bit mask for GPIO_EXTIPSEL3 */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL3_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL3_DEFAULT << 12) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_PORTA (_GPIO_EXTIPSELL_EXTIPSEL3_PORTA << 12) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_PORTB (_GPIO_EXTIPSELL_EXTIPSEL3_PORTB << 12) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_PORTC (_GPIO_EXTIPSELL_EXTIPSEL3_PORTC << 12) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_PORTD (_GPIO_EXTIPSELL_EXTIPSEL3_PORTD << 12) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_PORTE (_GPIO_EXTIPSELL_EXTIPSEL3_PORTE << 12) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL3_PORTF (_GPIO_EXTIPSELL_EXTIPSEL3_PORTF << 12) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_SHIFT 16 /**< Shift value for GPIO_EXTIPSEL4 */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_MASK 0x70000UL /**< Bit mask for GPIO_EXTIPSEL4 */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL4_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL4_DEFAULT << 16) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_PORTA (_GPIO_EXTIPSELL_EXTIPSEL4_PORTA << 16) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_PORTB (_GPIO_EXTIPSELL_EXTIPSEL4_PORTB << 16) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_PORTC (_GPIO_EXTIPSELL_EXTIPSEL4_PORTC << 16) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_PORTD (_GPIO_EXTIPSELL_EXTIPSEL4_PORTD << 16) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_PORTE (_GPIO_EXTIPSELL_EXTIPSEL4_PORTE << 16) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL4_PORTF (_GPIO_EXTIPSELL_EXTIPSEL4_PORTF << 16) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_SHIFT 20 /**< Shift value for GPIO_EXTIPSEL5 */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_MASK 0x700000UL /**< Bit mask for GPIO_EXTIPSEL5 */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL5_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL5_DEFAULT << 20) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_PORTA (_GPIO_EXTIPSELL_EXTIPSEL5_PORTA << 20) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_PORTB (_GPIO_EXTIPSELL_EXTIPSEL5_PORTB << 20) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_PORTC (_GPIO_EXTIPSELL_EXTIPSEL5_PORTC << 20) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_PORTD (_GPIO_EXTIPSELL_EXTIPSEL5_PORTD << 20) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_PORTE (_GPIO_EXTIPSELL_EXTIPSEL5_PORTE << 20) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL5_PORTF (_GPIO_EXTIPSELL_EXTIPSEL5_PORTF << 20) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_SHIFT 24 /**< Shift value for GPIO_EXTIPSEL6 */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_MASK 0x7000000UL /**< Bit mask for GPIO_EXTIPSEL6 */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL6_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL6_DEFAULT << 24) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_PORTA (_GPIO_EXTIPSELL_EXTIPSEL6_PORTA << 24) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_PORTB (_GPIO_EXTIPSELL_EXTIPSEL6_PORTB << 24) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_PORTC (_GPIO_EXTIPSELL_EXTIPSEL6_PORTC << 24) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_PORTD (_GPIO_EXTIPSELL_EXTIPSEL6_PORTD << 24) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_PORTE (_GPIO_EXTIPSELL_EXTIPSEL6_PORTE << 24) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL6_PORTF (_GPIO_EXTIPSELL_EXTIPSEL6_PORTF << 24) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_SHIFT 28 /**< Shift value for GPIO_EXTIPSEL7 */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_MASK 0x70000000UL /**< Bit mask for GPIO_EXTIPSEL7 */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELL */
-#define _GPIO_EXTIPSELL_EXTIPSEL7_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_DEFAULT (_GPIO_EXTIPSELL_EXTIPSEL7_DEFAULT << 28) /**< Shifted mode DEFAULT for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_PORTA (_GPIO_EXTIPSELL_EXTIPSEL7_PORTA << 28) /**< Shifted mode PORTA for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_PORTB (_GPIO_EXTIPSELL_EXTIPSEL7_PORTB << 28) /**< Shifted mode PORTB for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_PORTC (_GPIO_EXTIPSELL_EXTIPSEL7_PORTC << 28) /**< Shifted mode PORTC for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_PORTD (_GPIO_EXTIPSELL_EXTIPSEL7_PORTD << 28) /**< Shifted mode PORTD for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_PORTE (_GPIO_EXTIPSELL_EXTIPSEL7_PORTE << 28) /**< Shifted mode PORTE for GPIO_EXTIPSELL */
-#define GPIO_EXTIPSELL_EXTIPSEL7_PORTF (_GPIO_EXTIPSELL_EXTIPSEL7_PORTF << 28) /**< Shifted mode PORTF for GPIO_EXTIPSELL */
-
-/* Bit fields for GPIO EXTIPSELH */
-#define _GPIO_EXTIPSELH_RESETVALUE 0x00000000UL /**< Default value for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_MASK 0x77777777UL /**< Mask for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_SHIFT 0 /**< Shift value for GPIO_EXTIPSEL8 */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_MASK 0x7UL /**< Bit mask for GPIO_EXTIPSEL8 */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL8_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL8_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_PORTA (_GPIO_EXTIPSELH_EXTIPSEL8_PORTA << 0) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_PORTB (_GPIO_EXTIPSELH_EXTIPSEL8_PORTB << 0) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_PORTC (_GPIO_EXTIPSELH_EXTIPSEL8_PORTC << 0) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_PORTD (_GPIO_EXTIPSELH_EXTIPSEL8_PORTD << 0) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_PORTE (_GPIO_EXTIPSELH_EXTIPSEL8_PORTE << 0) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL8_PORTF (_GPIO_EXTIPSELH_EXTIPSEL8_PORTF << 0) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_SHIFT 4 /**< Shift value for GPIO_EXTIPSEL9 */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_MASK 0x70UL /**< Bit mask for GPIO_EXTIPSEL9 */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL9_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL9_DEFAULT << 4) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_PORTA (_GPIO_EXTIPSELH_EXTIPSEL9_PORTA << 4) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_PORTB (_GPIO_EXTIPSELH_EXTIPSEL9_PORTB << 4) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_PORTC (_GPIO_EXTIPSELH_EXTIPSEL9_PORTC << 4) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_PORTD (_GPIO_EXTIPSELH_EXTIPSEL9_PORTD << 4) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_PORTE (_GPIO_EXTIPSELH_EXTIPSEL9_PORTE << 4) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL9_PORTF (_GPIO_EXTIPSELH_EXTIPSEL9_PORTF << 4) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_SHIFT 8 /**< Shift value for GPIO_EXTIPSEL10 */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_MASK 0x700UL /**< Bit mask for GPIO_EXTIPSEL10 */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL10_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL10_DEFAULT << 8) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_PORTA (_GPIO_EXTIPSELH_EXTIPSEL10_PORTA << 8) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_PORTB (_GPIO_EXTIPSELH_EXTIPSEL10_PORTB << 8) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_PORTC (_GPIO_EXTIPSELH_EXTIPSEL10_PORTC << 8) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_PORTD (_GPIO_EXTIPSELH_EXTIPSEL10_PORTD << 8) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_PORTE (_GPIO_EXTIPSELH_EXTIPSEL10_PORTE << 8) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL10_PORTF (_GPIO_EXTIPSELH_EXTIPSEL10_PORTF << 8) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_SHIFT 12 /**< Shift value for GPIO_EXTIPSEL11 */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_MASK 0x7000UL /**< Bit mask for GPIO_EXTIPSEL11 */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL11_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL11_DEFAULT << 12) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_PORTA (_GPIO_EXTIPSELH_EXTIPSEL11_PORTA << 12) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_PORTB (_GPIO_EXTIPSELH_EXTIPSEL11_PORTB << 12) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_PORTC (_GPIO_EXTIPSELH_EXTIPSEL11_PORTC << 12) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_PORTD (_GPIO_EXTIPSELH_EXTIPSEL11_PORTD << 12) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_PORTE (_GPIO_EXTIPSELH_EXTIPSEL11_PORTE << 12) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL11_PORTF (_GPIO_EXTIPSELH_EXTIPSEL11_PORTF << 12) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_SHIFT 16 /**< Shift value for GPIO_EXTIPSEL12 */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_MASK 0x70000UL /**< Bit mask for GPIO_EXTIPSEL12 */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL12_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL12_DEFAULT << 16) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_PORTA (_GPIO_EXTIPSELH_EXTIPSEL12_PORTA << 16) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_PORTB (_GPIO_EXTIPSELH_EXTIPSEL12_PORTB << 16) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_PORTC (_GPIO_EXTIPSELH_EXTIPSEL12_PORTC << 16) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_PORTD (_GPIO_EXTIPSELH_EXTIPSEL12_PORTD << 16) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_PORTE (_GPIO_EXTIPSELH_EXTIPSEL12_PORTE << 16) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL12_PORTF (_GPIO_EXTIPSELH_EXTIPSEL12_PORTF << 16) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_SHIFT 20 /**< Shift value for GPIO_EXTIPSEL13 */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_MASK 0x700000UL /**< Bit mask for GPIO_EXTIPSEL13 */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL13_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL13_DEFAULT << 20) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_PORTA (_GPIO_EXTIPSELH_EXTIPSEL13_PORTA << 20) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_PORTB (_GPIO_EXTIPSELH_EXTIPSEL13_PORTB << 20) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_PORTC (_GPIO_EXTIPSELH_EXTIPSEL13_PORTC << 20) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_PORTD (_GPIO_EXTIPSELH_EXTIPSEL13_PORTD << 20) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_PORTE (_GPIO_EXTIPSELH_EXTIPSEL13_PORTE << 20) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL13_PORTF (_GPIO_EXTIPSELH_EXTIPSEL13_PORTF << 20) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_SHIFT 24 /**< Shift value for GPIO_EXTIPSEL14 */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_MASK 0x7000000UL /**< Bit mask for GPIO_EXTIPSEL14 */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL14_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL14_DEFAULT << 24) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_PORTA (_GPIO_EXTIPSELH_EXTIPSEL14_PORTA << 24) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_PORTB (_GPIO_EXTIPSELH_EXTIPSEL14_PORTB << 24) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_PORTC (_GPIO_EXTIPSELH_EXTIPSEL14_PORTC << 24) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_PORTD (_GPIO_EXTIPSELH_EXTIPSEL14_PORTD << 24) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_PORTE (_GPIO_EXTIPSELH_EXTIPSEL14_PORTE << 24) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL14_PORTF (_GPIO_EXTIPSELH_EXTIPSEL14_PORTF << 24) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_SHIFT 28 /**< Shift value for GPIO_EXTIPSEL15 */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_MASK 0x70000000UL /**< Bit mask for GPIO_EXTIPSEL15 */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_PORTA 0x00000000UL /**< Mode PORTA for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_PORTB 0x00000001UL /**< Mode PORTB for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_PORTC 0x00000002UL /**< Mode PORTC for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_PORTD 0x00000003UL /**< Mode PORTD for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_PORTE 0x00000004UL /**< Mode PORTE for GPIO_EXTIPSELH */
-#define _GPIO_EXTIPSELH_EXTIPSEL15_PORTF 0x00000005UL /**< Mode PORTF for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_DEFAULT (_GPIO_EXTIPSELH_EXTIPSEL15_DEFAULT << 28) /**< Shifted mode DEFAULT for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_PORTA (_GPIO_EXTIPSELH_EXTIPSEL15_PORTA << 28) /**< Shifted mode PORTA for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_PORTB (_GPIO_EXTIPSELH_EXTIPSEL15_PORTB << 28) /**< Shifted mode PORTB for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_PORTC (_GPIO_EXTIPSELH_EXTIPSEL15_PORTC << 28) /**< Shifted mode PORTC for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_PORTD (_GPIO_EXTIPSELH_EXTIPSEL15_PORTD << 28) /**< Shifted mode PORTD for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_PORTE (_GPIO_EXTIPSELH_EXTIPSEL15_PORTE << 28) /**< Shifted mode PORTE for GPIO_EXTIPSELH */
-#define GPIO_EXTIPSELH_EXTIPSEL15_PORTF (_GPIO_EXTIPSELH_EXTIPSEL15_PORTF << 28) /**< Shifted mode PORTF for GPIO_EXTIPSELH */
-
-/* Bit fields for GPIO EXTIRISE */
-#define _GPIO_EXTIRISE_RESETVALUE 0x00000000UL /**< Default value for GPIO_EXTIRISE */
-#define _GPIO_EXTIRISE_MASK 0x0000FFFFUL /**< Mask for GPIO_EXTIRISE */
-#define _GPIO_EXTIRISE_EXTIRISE_SHIFT 0 /**< Shift value for GPIO_EXTIRISE */
-#define _GPIO_EXTIRISE_EXTIRISE_MASK 0xFFFFUL /**< Bit mask for GPIO_EXTIRISE */
-#define _GPIO_EXTIRISE_EXTIRISE_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIRISE */
-#define GPIO_EXTIRISE_EXTIRISE_DEFAULT (_GPIO_EXTIRISE_EXTIRISE_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EXTIRISE */
-
-/* Bit fields for GPIO EXTIFALL */
-#define _GPIO_EXTIFALL_RESETVALUE 0x00000000UL /**< Default value for GPIO_EXTIFALL */
-#define _GPIO_EXTIFALL_MASK 0x0000FFFFUL /**< Mask for GPIO_EXTIFALL */
-#define _GPIO_EXTIFALL_EXTIFALL_SHIFT 0 /**< Shift value for GPIO_EXTIFALL */
-#define _GPIO_EXTIFALL_EXTIFALL_MASK 0xFFFFUL /**< Bit mask for GPIO_EXTIFALL */
-#define _GPIO_EXTIFALL_EXTIFALL_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EXTIFALL */
-#define GPIO_EXTIFALL_EXTIFALL_DEFAULT (_GPIO_EXTIFALL_EXTIFALL_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EXTIFALL */
-
-/* Bit fields for GPIO IEN */
-#define _GPIO_IEN_RESETVALUE 0x00000000UL /**< Default value for GPIO_IEN */
-#define _GPIO_IEN_MASK 0x0000FFFFUL /**< Mask for GPIO_IEN */
-#define _GPIO_IEN_EXT_SHIFT 0 /**< Shift value for GPIO_EXT */
-#define _GPIO_IEN_EXT_MASK 0xFFFFUL /**< Bit mask for GPIO_EXT */
-#define _GPIO_IEN_EXT_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_IEN */
-#define GPIO_IEN_EXT_DEFAULT (_GPIO_IEN_EXT_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_IEN */
-
-/* Bit fields for GPIO IF */
-#define _GPIO_IF_RESETVALUE 0x00000000UL /**< Default value for GPIO_IF */
-#define _GPIO_IF_MASK 0x0000FFFFUL /**< Mask for GPIO_IF */
-#define _GPIO_IF_EXT_SHIFT 0 /**< Shift value for GPIO_EXT */
-#define _GPIO_IF_EXT_MASK 0xFFFFUL /**< Bit mask for GPIO_EXT */
-#define _GPIO_IF_EXT_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_IF */
-#define GPIO_IF_EXT_DEFAULT (_GPIO_IF_EXT_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_IF */
-
-/* Bit fields for GPIO IFS */
-#define _GPIO_IFS_RESETVALUE 0x00000000UL /**< Default value for GPIO_IFS */
-#define _GPIO_IFS_MASK 0x0000FFFFUL /**< Mask for GPIO_IFS */
-#define _GPIO_IFS_EXT_SHIFT 0 /**< Shift value for GPIO_EXT */
-#define _GPIO_IFS_EXT_MASK 0xFFFFUL /**< Bit mask for GPIO_EXT */
-#define _GPIO_IFS_EXT_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_IFS */
-#define GPIO_IFS_EXT_DEFAULT (_GPIO_IFS_EXT_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_IFS */
-
-/* Bit fields for GPIO IFC */
-#define _GPIO_IFC_RESETVALUE 0x00000000UL /**< Default value for GPIO_IFC */
-#define _GPIO_IFC_MASK 0x0000FFFFUL /**< Mask for GPIO_IFC */
-#define _GPIO_IFC_EXT_SHIFT 0 /**< Shift value for GPIO_EXT */
-#define _GPIO_IFC_EXT_MASK 0xFFFFUL /**< Bit mask for GPIO_EXT */
-#define _GPIO_IFC_EXT_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_IFC */
-#define GPIO_IFC_EXT_DEFAULT (_GPIO_IFC_EXT_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_IFC */
-
-/* Bit fields for GPIO ROUTE */
-#define _GPIO_ROUTE_RESETVALUE 0x00000003UL /**< Default value for GPIO_ROUTE */
-#define _GPIO_ROUTE_MASK 0x00000003UL /**< Mask for GPIO_ROUTE */
-#define GPIO_ROUTE_SWCLKPEN (0x1UL << 0) /**< Serial Wire Clock Pin Enable */
-#define _GPIO_ROUTE_SWCLKPEN_SHIFT 0 /**< Shift value for GPIO_SWCLKPEN */
-#define _GPIO_ROUTE_SWCLKPEN_MASK 0x1UL /**< Bit mask for GPIO_SWCLKPEN */
-#define _GPIO_ROUTE_SWCLKPEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for GPIO_ROUTE */
-#define GPIO_ROUTE_SWCLKPEN_DEFAULT (_GPIO_ROUTE_SWCLKPEN_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_ROUTE */
-#define GPIO_ROUTE_SWDIOPEN (0x1UL << 1) /**< Serial Wire Data Pin Enable */
-#define _GPIO_ROUTE_SWDIOPEN_SHIFT 1 /**< Shift value for GPIO_SWDIOPEN */
-#define _GPIO_ROUTE_SWDIOPEN_MASK 0x2UL /**< Bit mask for GPIO_SWDIOPEN */
-#define _GPIO_ROUTE_SWDIOPEN_DEFAULT 0x00000001UL /**< Mode DEFAULT for GPIO_ROUTE */
-#define GPIO_ROUTE_SWDIOPEN_DEFAULT (_GPIO_ROUTE_SWDIOPEN_DEFAULT << 1) /**< Shifted mode DEFAULT for GPIO_ROUTE */
-
-/* Bit fields for GPIO INSENSE */
-#define _GPIO_INSENSE_RESETVALUE 0x00000003UL /**< Default value for GPIO_INSENSE */
-#define _GPIO_INSENSE_MASK 0x00000003UL /**< Mask for GPIO_INSENSE */
-#define GPIO_INSENSE_INT (0x1UL << 0) /**< Interrupt Sense Enable */
-#define _GPIO_INSENSE_INT_SHIFT 0 /**< Shift value for GPIO_INT */
-#define _GPIO_INSENSE_INT_MASK 0x1UL /**< Bit mask for GPIO_INT */
-#define _GPIO_INSENSE_INT_DEFAULT 0x00000001UL /**< Mode DEFAULT for GPIO_INSENSE */
-#define GPIO_INSENSE_INT_DEFAULT (_GPIO_INSENSE_INT_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_INSENSE */
-#define GPIO_INSENSE_PRS (0x1UL << 1) /**< PRS Sense Enable */
-#define _GPIO_INSENSE_PRS_SHIFT 1 /**< Shift value for GPIO_PRS */
-#define _GPIO_INSENSE_PRS_MASK 0x2UL /**< Bit mask for GPIO_PRS */
-#define _GPIO_INSENSE_PRS_DEFAULT 0x00000001UL /**< Mode DEFAULT for GPIO_INSENSE */
-#define GPIO_INSENSE_PRS_DEFAULT (_GPIO_INSENSE_PRS_DEFAULT << 1) /**< Shifted mode DEFAULT for GPIO_INSENSE */
-
-/* Bit fields for GPIO LOCK */
-#define _GPIO_LOCK_RESETVALUE 0x00000000UL /**< Default value for GPIO_LOCK */
-#define _GPIO_LOCK_MASK 0x0000FFFFUL /**< Mask for GPIO_LOCK */
-#define _GPIO_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for GPIO_LOCKKEY */
-#define _GPIO_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for GPIO_LOCKKEY */
-#define _GPIO_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_LOCK */
-#define _GPIO_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for GPIO_LOCK */
-#define _GPIO_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for GPIO_LOCK */
-#define _GPIO_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for GPIO_LOCK */
-#define _GPIO_LOCK_LOCKKEY_UNLOCK 0x0000A534UL /**< Mode UNLOCK for GPIO_LOCK */
-#define GPIO_LOCK_LOCKKEY_DEFAULT (_GPIO_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_LOCK */
-#define GPIO_LOCK_LOCKKEY_LOCK (_GPIO_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for GPIO_LOCK */
-#define GPIO_LOCK_LOCKKEY_UNLOCKED (_GPIO_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for GPIO_LOCK */
-#define GPIO_LOCK_LOCKKEY_LOCKED (_GPIO_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for GPIO_LOCK */
-#define GPIO_LOCK_LOCKKEY_UNLOCK (_GPIO_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for GPIO_LOCK */
-
-/* Bit fields for GPIO CTRL */
-#define _GPIO_CTRL_RESETVALUE 0x00000000UL /**< Default value for GPIO_CTRL */
-#define _GPIO_CTRL_MASK 0x00000001UL /**< Mask for GPIO_CTRL */
-#define GPIO_CTRL_EM4RET (0x1UL << 0) /**< Enable EM4 retention */
-#define _GPIO_CTRL_EM4RET_SHIFT 0 /**< Shift value for GPIO_EM4RET */
-#define _GPIO_CTRL_EM4RET_MASK 0x1UL /**< Bit mask for GPIO_EM4RET */
-#define _GPIO_CTRL_EM4RET_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_CTRL */
-#define GPIO_CTRL_EM4RET_DEFAULT (_GPIO_CTRL_EM4RET_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_CTRL */
-
-/* Bit fields for GPIO CMD */
-#define _GPIO_CMD_RESETVALUE 0x00000000UL /**< Default value for GPIO_CMD */
-#define _GPIO_CMD_MASK 0x00000001UL /**< Mask for GPIO_CMD */
-#define GPIO_CMD_EM4WUCLR (0x1UL << 0) /**< EM4 Wake-up clear */
-#define _GPIO_CMD_EM4WUCLR_SHIFT 0 /**< Shift value for GPIO_EM4WUCLR */
-#define _GPIO_CMD_EM4WUCLR_MASK 0x1UL /**< Bit mask for GPIO_EM4WUCLR */
-#define _GPIO_CMD_EM4WUCLR_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_CMD */
-#define GPIO_CMD_EM4WUCLR_DEFAULT (_GPIO_CMD_EM4WUCLR_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_CMD */
-
-/* Bit fields for GPIO EM4WUEN */
-#define _GPIO_EM4WUEN_RESETVALUE 0x00000000UL /**< Default value for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_MASK 0x0000003FUL /**< Mask for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_SHIFT 0 /**< Shift value for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_MASK 0x3FUL /**< Bit mask for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_A0 0x00000001UL /**< Mode A0 for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_C9 0x00000004UL /**< Mode C9 for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_F1 0x00000008UL /**< Mode F1 for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_F2 0x00000010UL /**< Mode F2 for GPIO_EM4WUEN */
-#define _GPIO_EM4WUEN_EM4WUEN_E13 0x00000020UL /**< Mode E13 for GPIO_EM4WUEN */
-#define GPIO_EM4WUEN_EM4WUEN_DEFAULT (_GPIO_EM4WUEN_EM4WUEN_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EM4WUEN */
-#define GPIO_EM4WUEN_EM4WUEN_A0 (_GPIO_EM4WUEN_EM4WUEN_A0 << 0) /**< Shifted mode A0 for GPIO_EM4WUEN */
-#define GPIO_EM4WUEN_EM4WUEN_C9 (_GPIO_EM4WUEN_EM4WUEN_C9 << 0) /**< Shifted mode C9 for GPIO_EM4WUEN */
-#define GPIO_EM4WUEN_EM4WUEN_F1 (_GPIO_EM4WUEN_EM4WUEN_F1 << 0) /**< Shifted mode F1 for GPIO_EM4WUEN */
-#define GPIO_EM4WUEN_EM4WUEN_F2 (_GPIO_EM4WUEN_EM4WUEN_F2 << 0) /**< Shifted mode F2 for GPIO_EM4WUEN */
-#define GPIO_EM4WUEN_EM4WUEN_E13 (_GPIO_EM4WUEN_EM4WUEN_E13 << 0) /**< Shifted mode E13 for GPIO_EM4WUEN */
-
-/* Bit fields for GPIO EM4WUPOL */
-#define _GPIO_EM4WUPOL_RESETVALUE 0x00000000UL /**< Default value for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_MASK 0x0000003FUL /**< Mask for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_SHIFT 0 /**< Shift value for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_MASK 0x3FUL /**< Bit mask for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_A0 0x00000001UL /**< Mode A0 for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_C9 0x00000004UL /**< Mode C9 for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_F1 0x00000008UL /**< Mode F1 for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_F2 0x00000010UL /**< Mode F2 for GPIO_EM4WUPOL */
-#define _GPIO_EM4WUPOL_EM4WUPOL_E13 0x00000020UL /**< Mode E13 for GPIO_EM4WUPOL */
-#define GPIO_EM4WUPOL_EM4WUPOL_DEFAULT (_GPIO_EM4WUPOL_EM4WUPOL_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EM4WUPOL */
-#define GPIO_EM4WUPOL_EM4WUPOL_A0 (_GPIO_EM4WUPOL_EM4WUPOL_A0 << 0) /**< Shifted mode A0 for GPIO_EM4WUPOL */
-#define GPIO_EM4WUPOL_EM4WUPOL_C9 (_GPIO_EM4WUPOL_EM4WUPOL_C9 << 0) /**< Shifted mode C9 for GPIO_EM4WUPOL */
-#define GPIO_EM4WUPOL_EM4WUPOL_F1 (_GPIO_EM4WUPOL_EM4WUPOL_F1 << 0) /**< Shifted mode F1 for GPIO_EM4WUPOL */
-#define GPIO_EM4WUPOL_EM4WUPOL_F2 (_GPIO_EM4WUPOL_EM4WUPOL_F2 << 0) /**< Shifted mode F2 for GPIO_EM4WUPOL */
-#define GPIO_EM4WUPOL_EM4WUPOL_E13 (_GPIO_EM4WUPOL_EM4WUPOL_E13 << 0) /**< Shifted mode E13 for GPIO_EM4WUPOL */
-
-/* Bit fields for GPIO EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_RESETVALUE 0x00000000UL /**< Default value for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_MASK 0x0000003FUL /**< Mask for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_SHIFT 0 /**< Shift value for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_MASK 0x3FUL /**< Bit mask for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_A0 0x00000001UL /**< Mode A0 for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_C9 0x00000004UL /**< Mode C9 for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_F1 0x00000008UL /**< Mode F1 for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_F2 0x00000010UL /**< Mode F2 for GPIO_EM4WUCAUSE */
-#define _GPIO_EM4WUCAUSE_EM4WUCAUSE_E13 0x00000020UL /**< Mode E13 for GPIO_EM4WUCAUSE */
-#define GPIO_EM4WUCAUSE_EM4WUCAUSE_DEFAULT (_GPIO_EM4WUCAUSE_EM4WUCAUSE_DEFAULT << 0) /**< Shifted mode DEFAULT for GPIO_EM4WUCAUSE */
-#define GPIO_EM4WUCAUSE_EM4WUCAUSE_A0 (_GPIO_EM4WUCAUSE_EM4WUCAUSE_A0 << 0) /**< Shifted mode A0 for GPIO_EM4WUCAUSE */
-#define GPIO_EM4WUCAUSE_EM4WUCAUSE_C9 (_GPIO_EM4WUCAUSE_EM4WUCAUSE_C9 << 0) /**< Shifted mode C9 for GPIO_EM4WUCAUSE */
-#define GPIO_EM4WUCAUSE_EM4WUCAUSE_F1 (_GPIO_EM4WUCAUSE_EM4WUCAUSE_F1 << 0) /**< Shifted mode F1 for GPIO_EM4WUCAUSE */
-#define GPIO_EM4WUCAUSE_EM4WUCAUSE_F2 (_GPIO_EM4WUCAUSE_EM4WUCAUSE_F2 << 0) /**< Shifted mode F2 for GPIO_EM4WUCAUSE */
-#define GPIO_EM4WUCAUSE_EM4WUCAUSE_E13 (_GPIO_EM4WUCAUSE_EM4WUCAUSE_E13 << 0) /**< Shifted mode E13 for GPIO_EM4WUCAUSE */
-
-/** @} End of group EFM32ZG_GPIO */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_gpio_p.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_gpio_p.h
deleted file mode 100644
index 6ce6132bd3..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_gpio_p.h
+++ /dev/null
@@ -1,56 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_GPIO_P register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @brief GPIO_P EFM32ZG GPIO P
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Port Control Register */
- __IOM uint32_t MODEL; /**< Port Pin Mode Low Register */
- __IOM uint32_t MODEH; /**< Port Pin Mode High Register */
- __IOM uint32_t DOUT; /**< Port Data Out Register */
- __OM uint32_t DOUTSET; /**< Port Data Out Set Register */
- __OM uint32_t DOUTCLR; /**< Port Data Out Clear Register */
- __OM uint32_t DOUTTGL; /**< Port Data Out Toggle Register */
- __IM uint32_t DIN; /**< Port Data In Register */
- __IOM uint32_t PINLOCKN; /**< Port Unlocked Pins Register */
-} GPIO_P_TypeDef;
-
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_i2c.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_i2c.h
deleted file mode 100644
index 51bdaec5a5..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_i2c.h
+++ /dev/null
@@ -1,708 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_I2C register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_I2C
- * @{
- * @brief EFM32ZG_I2C Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATE; /**< State Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t CLKDIV; /**< Clock Division Register */
- __IOM uint32_t SADDR; /**< Slave Address Register */
- __IOM uint32_t SADDRMASK; /**< Slave Address Mask Register */
- __IM uint32_t RXDATA; /**< Receive Buffer Data Register */
- __IM uint32_t RXDATAP; /**< Receive Buffer Data Peek Register */
- __IOM uint32_t TXDATA; /**< Transmit Buffer Data Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-} I2C_TypeDef; /** I2C Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_I2C_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for I2C CTRL */
-#define _I2C_CTRL_RESETVALUE 0x00000000UL /**< Default value for I2C_CTRL */
-#define _I2C_CTRL_MASK 0x0007B37FUL /**< Mask for I2C_CTRL */
-#define I2C_CTRL_EN (0x1UL << 0) /**< I2C Enable */
-#define _I2C_CTRL_EN_SHIFT 0 /**< Shift value for I2C_EN */
-#define _I2C_CTRL_EN_MASK 0x1UL /**< Bit mask for I2C_EN */
-#define _I2C_CTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_EN_DEFAULT (_I2C_CTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_SLAVE (0x1UL << 1) /**< Addressable as Slave */
-#define _I2C_CTRL_SLAVE_SHIFT 1 /**< Shift value for I2C_SLAVE */
-#define _I2C_CTRL_SLAVE_MASK 0x2UL /**< Bit mask for I2C_SLAVE */
-#define _I2C_CTRL_SLAVE_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_SLAVE_DEFAULT (_I2C_CTRL_SLAVE_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_AUTOACK (0x1UL << 2) /**< Automatic Acknowledge */
-#define _I2C_CTRL_AUTOACK_SHIFT 2 /**< Shift value for I2C_AUTOACK */
-#define _I2C_CTRL_AUTOACK_MASK 0x4UL /**< Bit mask for I2C_AUTOACK */
-#define _I2C_CTRL_AUTOACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_AUTOACK_DEFAULT (_I2C_CTRL_AUTOACK_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_AUTOSE (0x1UL << 3) /**< Automatic STOP when Empty */
-#define _I2C_CTRL_AUTOSE_SHIFT 3 /**< Shift value for I2C_AUTOSE */
-#define _I2C_CTRL_AUTOSE_MASK 0x8UL /**< Bit mask for I2C_AUTOSE */
-#define _I2C_CTRL_AUTOSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_AUTOSE_DEFAULT (_I2C_CTRL_AUTOSE_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_AUTOSN (0x1UL << 4) /**< Automatic STOP on NACK */
-#define _I2C_CTRL_AUTOSN_SHIFT 4 /**< Shift value for I2C_AUTOSN */
-#define _I2C_CTRL_AUTOSN_MASK 0x10UL /**< Bit mask for I2C_AUTOSN */
-#define _I2C_CTRL_AUTOSN_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_AUTOSN_DEFAULT (_I2C_CTRL_AUTOSN_DEFAULT << 4) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_ARBDIS (0x1UL << 5) /**< Arbitration Disable */
-#define _I2C_CTRL_ARBDIS_SHIFT 5 /**< Shift value for I2C_ARBDIS */
-#define _I2C_CTRL_ARBDIS_MASK 0x20UL /**< Bit mask for I2C_ARBDIS */
-#define _I2C_CTRL_ARBDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_ARBDIS_DEFAULT (_I2C_CTRL_ARBDIS_DEFAULT << 5) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_GCAMEN (0x1UL << 6) /**< General Call Address Match Enable */
-#define _I2C_CTRL_GCAMEN_SHIFT 6 /**< Shift value for I2C_GCAMEN */
-#define _I2C_CTRL_GCAMEN_MASK 0x40UL /**< Bit mask for I2C_GCAMEN */
-#define _I2C_CTRL_GCAMEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_GCAMEN_DEFAULT (_I2C_CTRL_GCAMEN_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define _I2C_CTRL_CLHR_SHIFT 8 /**< Shift value for I2C_CLHR */
-#define _I2C_CTRL_CLHR_MASK 0x300UL /**< Bit mask for I2C_CLHR */
-#define _I2C_CTRL_CLHR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define _I2C_CTRL_CLHR_STANDARD 0x00000000UL /**< Mode STANDARD for I2C_CTRL */
-#define _I2C_CTRL_CLHR_ASYMMETRIC 0x00000001UL /**< Mode ASYMMETRIC for I2C_CTRL */
-#define _I2C_CTRL_CLHR_FAST 0x00000002UL /**< Mode FAST for I2C_CTRL */
-#define I2C_CTRL_CLHR_DEFAULT (_I2C_CTRL_CLHR_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_CLHR_STANDARD (_I2C_CTRL_CLHR_STANDARD << 8) /**< Shifted mode STANDARD for I2C_CTRL */
-#define I2C_CTRL_CLHR_ASYMMETRIC (_I2C_CTRL_CLHR_ASYMMETRIC << 8) /**< Shifted mode ASYMMETRIC for I2C_CTRL */
-#define I2C_CTRL_CLHR_FAST (_I2C_CTRL_CLHR_FAST << 8) /**< Shifted mode FAST for I2C_CTRL */
-#define _I2C_CTRL_BITO_SHIFT 12 /**< Shift value for I2C_BITO */
-#define _I2C_CTRL_BITO_MASK 0x3000UL /**< Bit mask for I2C_BITO */
-#define _I2C_CTRL_BITO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define _I2C_CTRL_BITO_OFF 0x00000000UL /**< Mode OFF for I2C_CTRL */
-#define _I2C_CTRL_BITO_40PCC 0x00000001UL /**< Mode 40PCC for I2C_CTRL */
-#define _I2C_CTRL_BITO_80PCC 0x00000002UL /**< Mode 80PCC for I2C_CTRL */
-#define _I2C_CTRL_BITO_160PCC 0x00000003UL /**< Mode 160PCC for I2C_CTRL */
-#define I2C_CTRL_BITO_DEFAULT (_I2C_CTRL_BITO_DEFAULT << 12) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_BITO_OFF (_I2C_CTRL_BITO_OFF << 12) /**< Shifted mode OFF for I2C_CTRL */
-#define I2C_CTRL_BITO_40PCC (_I2C_CTRL_BITO_40PCC << 12) /**< Shifted mode 40PCC for I2C_CTRL */
-#define I2C_CTRL_BITO_80PCC (_I2C_CTRL_BITO_80PCC << 12) /**< Shifted mode 80PCC for I2C_CTRL */
-#define I2C_CTRL_BITO_160PCC (_I2C_CTRL_BITO_160PCC << 12) /**< Shifted mode 160PCC for I2C_CTRL */
-#define I2C_CTRL_GIBITO (0x1UL << 15) /**< Go Idle on Bus Idle Timeout */
-#define _I2C_CTRL_GIBITO_SHIFT 15 /**< Shift value for I2C_GIBITO */
-#define _I2C_CTRL_GIBITO_MASK 0x8000UL /**< Bit mask for I2C_GIBITO */
-#define _I2C_CTRL_GIBITO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_GIBITO_DEFAULT (_I2C_CTRL_GIBITO_DEFAULT << 15) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define _I2C_CTRL_CLTO_SHIFT 16 /**< Shift value for I2C_CLTO */
-#define _I2C_CTRL_CLTO_MASK 0x70000UL /**< Bit mask for I2C_CLTO */
-#define _I2C_CTRL_CLTO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CTRL */
-#define _I2C_CTRL_CLTO_OFF 0x00000000UL /**< Mode OFF for I2C_CTRL */
-#define _I2C_CTRL_CLTO_40PCC 0x00000001UL /**< Mode 40PCC for I2C_CTRL */
-#define _I2C_CTRL_CLTO_80PCC 0x00000002UL /**< Mode 80PCC for I2C_CTRL */
-#define _I2C_CTRL_CLTO_160PCC 0x00000003UL /**< Mode 160PCC for I2C_CTRL */
-#define _I2C_CTRL_CLTO_320PPC 0x00000004UL /**< Mode 320PPC for I2C_CTRL */
-#define _I2C_CTRL_CLTO_1024PPC 0x00000005UL /**< Mode 1024PPC for I2C_CTRL */
-#define I2C_CTRL_CLTO_DEFAULT (_I2C_CTRL_CLTO_DEFAULT << 16) /**< Shifted mode DEFAULT for I2C_CTRL */
-#define I2C_CTRL_CLTO_OFF (_I2C_CTRL_CLTO_OFF << 16) /**< Shifted mode OFF for I2C_CTRL */
-#define I2C_CTRL_CLTO_40PCC (_I2C_CTRL_CLTO_40PCC << 16) /**< Shifted mode 40PCC for I2C_CTRL */
-#define I2C_CTRL_CLTO_80PCC (_I2C_CTRL_CLTO_80PCC << 16) /**< Shifted mode 80PCC for I2C_CTRL */
-#define I2C_CTRL_CLTO_160PCC (_I2C_CTRL_CLTO_160PCC << 16) /**< Shifted mode 160PCC for I2C_CTRL */
-#define I2C_CTRL_CLTO_320PPC (_I2C_CTRL_CLTO_320PPC << 16) /**< Shifted mode 320PPC for I2C_CTRL */
-#define I2C_CTRL_CLTO_1024PPC (_I2C_CTRL_CLTO_1024PPC << 16) /**< Shifted mode 1024PPC for I2C_CTRL */
-
-/* Bit fields for I2C CMD */
-#define _I2C_CMD_RESETVALUE 0x00000000UL /**< Default value for I2C_CMD */
-#define _I2C_CMD_MASK 0x000000FFUL /**< Mask for I2C_CMD */
-#define I2C_CMD_START (0x1UL << 0) /**< Send start condition */
-#define _I2C_CMD_START_SHIFT 0 /**< Shift value for I2C_START */
-#define _I2C_CMD_START_MASK 0x1UL /**< Bit mask for I2C_START */
-#define _I2C_CMD_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_START_DEFAULT (_I2C_CMD_START_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_STOP (0x1UL << 1) /**< Send stop condition */
-#define _I2C_CMD_STOP_SHIFT 1 /**< Shift value for I2C_STOP */
-#define _I2C_CMD_STOP_MASK 0x2UL /**< Bit mask for I2C_STOP */
-#define _I2C_CMD_STOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_STOP_DEFAULT (_I2C_CMD_STOP_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_ACK (0x1UL << 2) /**< Send ACK */
-#define _I2C_CMD_ACK_SHIFT 2 /**< Shift value for I2C_ACK */
-#define _I2C_CMD_ACK_MASK 0x4UL /**< Bit mask for I2C_ACK */
-#define _I2C_CMD_ACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_ACK_DEFAULT (_I2C_CMD_ACK_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_NACK (0x1UL << 3) /**< Send NACK */
-#define _I2C_CMD_NACK_SHIFT 3 /**< Shift value for I2C_NACK */
-#define _I2C_CMD_NACK_MASK 0x8UL /**< Bit mask for I2C_NACK */
-#define _I2C_CMD_NACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_NACK_DEFAULT (_I2C_CMD_NACK_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_CONT (0x1UL << 4) /**< Continue transmission */
-#define _I2C_CMD_CONT_SHIFT 4 /**< Shift value for I2C_CONT */
-#define _I2C_CMD_CONT_MASK 0x10UL /**< Bit mask for I2C_CONT */
-#define _I2C_CMD_CONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_CONT_DEFAULT (_I2C_CMD_CONT_DEFAULT << 4) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_ABORT (0x1UL << 5) /**< Abort transmission */
-#define _I2C_CMD_ABORT_SHIFT 5 /**< Shift value for I2C_ABORT */
-#define _I2C_CMD_ABORT_MASK 0x20UL /**< Bit mask for I2C_ABORT */
-#define _I2C_CMD_ABORT_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_ABORT_DEFAULT (_I2C_CMD_ABORT_DEFAULT << 5) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_CLEARTX (0x1UL << 6) /**< Clear TX */
-#define _I2C_CMD_CLEARTX_SHIFT 6 /**< Shift value for I2C_CLEARTX */
-#define _I2C_CMD_CLEARTX_MASK 0x40UL /**< Bit mask for I2C_CLEARTX */
-#define _I2C_CMD_CLEARTX_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_CLEARTX_DEFAULT (_I2C_CMD_CLEARTX_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_CMD */
-#define I2C_CMD_CLEARPC (0x1UL << 7) /**< Clear Pending Commands */
-#define _I2C_CMD_CLEARPC_SHIFT 7 /**< Shift value for I2C_CLEARPC */
-#define _I2C_CMD_CLEARPC_MASK 0x80UL /**< Bit mask for I2C_CLEARPC */
-#define _I2C_CMD_CLEARPC_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CMD */
-#define I2C_CMD_CLEARPC_DEFAULT (_I2C_CMD_CLEARPC_DEFAULT << 7) /**< Shifted mode DEFAULT for I2C_CMD */
-
-/* Bit fields for I2C STATE */
-#define _I2C_STATE_RESETVALUE 0x00000001UL /**< Default value for I2C_STATE */
-#define _I2C_STATE_MASK 0x000000FFUL /**< Mask for I2C_STATE */
-#define I2C_STATE_BUSY (0x1UL << 0) /**< Bus Busy */
-#define _I2C_STATE_BUSY_SHIFT 0 /**< Shift value for I2C_BUSY */
-#define _I2C_STATE_BUSY_MASK 0x1UL /**< Bit mask for I2C_BUSY */
-#define _I2C_STATE_BUSY_DEFAULT 0x00000001UL /**< Mode DEFAULT for I2C_STATE */
-#define I2C_STATE_BUSY_DEFAULT (_I2C_STATE_BUSY_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_STATE */
-#define I2C_STATE_MASTER (0x1UL << 1) /**< Master */
-#define _I2C_STATE_MASTER_SHIFT 1 /**< Shift value for I2C_MASTER */
-#define _I2C_STATE_MASTER_MASK 0x2UL /**< Bit mask for I2C_MASTER */
-#define _I2C_STATE_MASTER_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATE */
-#define I2C_STATE_MASTER_DEFAULT (_I2C_STATE_MASTER_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_STATE */
-#define I2C_STATE_TRANSMITTER (0x1UL << 2) /**< Transmitter */
-#define _I2C_STATE_TRANSMITTER_SHIFT 2 /**< Shift value for I2C_TRANSMITTER */
-#define _I2C_STATE_TRANSMITTER_MASK 0x4UL /**< Bit mask for I2C_TRANSMITTER */
-#define _I2C_STATE_TRANSMITTER_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATE */
-#define I2C_STATE_TRANSMITTER_DEFAULT (_I2C_STATE_TRANSMITTER_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_STATE */
-#define I2C_STATE_NACKED (0x1UL << 3) /**< Nack Received */
-#define _I2C_STATE_NACKED_SHIFT 3 /**< Shift value for I2C_NACKED */
-#define _I2C_STATE_NACKED_MASK 0x8UL /**< Bit mask for I2C_NACKED */
-#define _I2C_STATE_NACKED_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATE */
-#define I2C_STATE_NACKED_DEFAULT (_I2C_STATE_NACKED_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_STATE */
-#define I2C_STATE_BUSHOLD (0x1UL << 4) /**< Bus Held */
-#define _I2C_STATE_BUSHOLD_SHIFT 4 /**< Shift value for I2C_BUSHOLD */
-#define _I2C_STATE_BUSHOLD_MASK 0x10UL /**< Bit mask for I2C_BUSHOLD */
-#define _I2C_STATE_BUSHOLD_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATE */
-#define I2C_STATE_BUSHOLD_DEFAULT (_I2C_STATE_BUSHOLD_DEFAULT << 4) /**< Shifted mode DEFAULT for I2C_STATE */
-#define _I2C_STATE_STATE_SHIFT 5 /**< Shift value for I2C_STATE */
-#define _I2C_STATE_STATE_MASK 0xE0UL /**< Bit mask for I2C_STATE */
-#define _I2C_STATE_STATE_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATE */
-#define _I2C_STATE_STATE_IDLE 0x00000000UL /**< Mode IDLE for I2C_STATE */
-#define _I2C_STATE_STATE_WAIT 0x00000001UL /**< Mode WAIT for I2C_STATE */
-#define _I2C_STATE_STATE_START 0x00000002UL /**< Mode START for I2C_STATE */
-#define _I2C_STATE_STATE_ADDR 0x00000003UL /**< Mode ADDR for I2C_STATE */
-#define _I2C_STATE_STATE_ADDRACK 0x00000004UL /**< Mode ADDRACK for I2C_STATE */
-#define _I2C_STATE_STATE_DATA 0x00000005UL /**< Mode DATA for I2C_STATE */
-#define _I2C_STATE_STATE_DATAACK 0x00000006UL /**< Mode DATAACK for I2C_STATE */
-#define I2C_STATE_STATE_DEFAULT (_I2C_STATE_STATE_DEFAULT << 5) /**< Shifted mode DEFAULT for I2C_STATE */
-#define I2C_STATE_STATE_IDLE (_I2C_STATE_STATE_IDLE << 5) /**< Shifted mode IDLE for I2C_STATE */
-#define I2C_STATE_STATE_WAIT (_I2C_STATE_STATE_WAIT << 5) /**< Shifted mode WAIT for I2C_STATE */
-#define I2C_STATE_STATE_START (_I2C_STATE_STATE_START << 5) /**< Shifted mode START for I2C_STATE */
-#define I2C_STATE_STATE_ADDR (_I2C_STATE_STATE_ADDR << 5) /**< Shifted mode ADDR for I2C_STATE */
-#define I2C_STATE_STATE_ADDRACK (_I2C_STATE_STATE_ADDRACK << 5) /**< Shifted mode ADDRACK for I2C_STATE */
-#define I2C_STATE_STATE_DATA (_I2C_STATE_STATE_DATA << 5) /**< Shifted mode DATA for I2C_STATE */
-#define I2C_STATE_STATE_DATAACK (_I2C_STATE_STATE_DATAACK << 5) /**< Shifted mode DATAACK for I2C_STATE */
-
-/* Bit fields for I2C STATUS */
-#define _I2C_STATUS_RESETVALUE 0x00000080UL /**< Default value for I2C_STATUS */
-#define _I2C_STATUS_MASK 0x000001FFUL /**< Mask for I2C_STATUS */
-#define I2C_STATUS_PSTART (0x1UL << 0) /**< Pending START */
-#define _I2C_STATUS_PSTART_SHIFT 0 /**< Shift value for I2C_PSTART */
-#define _I2C_STATUS_PSTART_MASK 0x1UL /**< Bit mask for I2C_PSTART */
-#define _I2C_STATUS_PSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PSTART_DEFAULT (_I2C_STATUS_PSTART_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PSTOP (0x1UL << 1) /**< Pending STOP */
-#define _I2C_STATUS_PSTOP_SHIFT 1 /**< Shift value for I2C_PSTOP */
-#define _I2C_STATUS_PSTOP_MASK 0x2UL /**< Bit mask for I2C_PSTOP */
-#define _I2C_STATUS_PSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PSTOP_DEFAULT (_I2C_STATUS_PSTOP_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PACK (0x1UL << 2) /**< Pending ACK */
-#define _I2C_STATUS_PACK_SHIFT 2 /**< Shift value for I2C_PACK */
-#define _I2C_STATUS_PACK_MASK 0x4UL /**< Bit mask for I2C_PACK */
-#define _I2C_STATUS_PACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PACK_DEFAULT (_I2C_STATUS_PACK_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PNACK (0x1UL << 3) /**< Pending NACK */
-#define _I2C_STATUS_PNACK_SHIFT 3 /**< Shift value for I2C_PNACK */
-#define _I2C_STATUS_PNACK_MASK 0x8UL /**< Bit mask for I2C_PNACK */
-#define _I2C_STATUS_PNACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PNACK_DEFAULT (_I2C_STATUS_PNACK_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PCONT (0x1UL << 4) /**< Pending continue */
-#define _I2C_STATUS_PCONT_SHIFT 4 /**< Shift value for I2C_PCONT */
-#define _I2C_STATUS_PCONT_MASK 0x10UL /**< Bit mask for I2C_PCONT */
-#define _I2C_STATUS_PCONT_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PCONT_DEFAULT (_I2C_STATUS_PCONT_DEFAULT << 4) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PABORT (0x1UL << 5) /**< Pending abort */
-#define _I2C_STATUS_PABORT_SHIFT 5 /**< Shift value for I2C_PABORT */
-#define _I2C_STATUS_PABORT_MASK 0x20UL /**< Bit mask for I2C_PABORT */
-#define _I2C_STATUS_PABORT_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_PABORT_DEFAULT (_I2C_STATUS_PABORT_DEFAULT << 5) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_TXC (0x1UL << 6) /**< TX Complete */
-#define _I2C_STATUS_TXC_SHIFT 6 /**< Shift value for I2C_TXC */
-#define _I2C_STATUS_TXC_MASK 0x40UL /**< Bit mask for I2C_TXC */
-#define _I2C_STATUS_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_TXC_DEFAULT (_I2C_STATUS_TXC_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_TXBL (0x1UL << 7) /**< TX Buffer Level */
-#define _I2C_STATUS_TXBL_SHIFT 7 /**< Shift value for I2C_TXBL */
-#define _I2C_STATUS_TXBL_MASK 0x80UL /**< Bit mask for I2C_TXBL */
-#define _I2C_STATUS_TXBL_DEFAULT 0x00000001UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_TXBL_DEFAULT (_I2C_STATUS_TXBL_DEFAULT << 7) /**< Shifted mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_RXDATAV (0x1UL << 8) /**< RX Data Valid */
-#define _I2C_STATUS_RXDATAV_SHIFT 8 /**< Shift value for I2C_RXDATAV */
-#define _I2C_STATUS_RXDATAV_MASK 0x100UL /**< Bit mask for I2C_RXDATAV */
-#define _I2C_STATUS_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_STATUS */
-#define I2C_STATUS_RXDATAV_DEFAULT (_I2C_STATUS_RXDATAV_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_STATUS */
-
-/* Bit fields for I2C CLKDIV */
-#define _I2C_CLKDIV_RESETVALUE 0x00000000UL /**< Default value for I2C_CLKDIV */
-#define _I2C_CLKDIV_MASK 0x000001FFUL /**< Mask for I2C_CLKDIV */
-#define _I2C_CLKDIV_DIV_SHIFT 0 /**< Shift value for I2C_DIV */
-#define _I2C_CLKDIV_DIV_MASK 0x1FFUL /**< Bit mask for I2C_DIV */
-#define _I2C_CLKDIV_DIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_CLKDIV */
-#define I2C_CLKDIV_DIV_DEFAULT (_I2C_CLKDIV_DIV_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_CLKDIV */
-
-/* Bit fields for I2C SADDR */
-#define _I2C_SADDR_RESETVALUE 0x00000000UL /**< Default value for I2C_SADDR */
-#define _I2C_SADDR_MASK 0x000000FEUL /**< Mask for I2C_SADDR */
-#define _I2C_SADDR_ADDR_SHIFT 1 /**< Shift value for I2C_ADDR */
-#define _I2C_SADDR_ADDR_MASK 0xFEUL /**< Bit mask for I2C_ADDR */
-#define _I2C_SADDR_ADDR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_SADDR */
-#define I2C_SADDR_ADDR_DEFAULT (_I2C_SADDR_ADDR_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_SADDR */
-
-/* Bit fields for I2C SADDRMASK */
-#define _I2C_SADDRMASK_RESETVALUE 0x00000000UL /**< Default value for I2C_SADDRMASK */
-#define _I2C_SADDRMASK_MASK 0x000000FEUL /**< Mask for I2C_SADDRMASK */
-#define _I2C_SADDRMASK_MASK_SHIFT 1 /**< Shift value for I2C_MASK */
-#define _I2C_SADDRMASK_MASK_MASK 0xFEUL /**< Bit mask for I2C_MASK */
-#define _I2C_SADDRMASK_MASK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_SADDRMASK */
-#define I2C_SADDRMASK_MASK_DEFAULT (_I2C_SADDRMASK_MASK_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_SADDRMASK */
-
-/* Bit fields for I2C RXDATA */
-#define _I2C_RXDATA_RESETVALUE 0x00000000UL /**< Default value for I2C_RXDATA */
-#define _I2C_RXDATA_MASK 0x000000FFUL /**< Mask for I2C_RXDATA */
-#define _I2C_RXDATA_RXDATA_SHIFT 0 /**< Shift value for I2C_RXDATA */
-#define _I2C_RXDATA_RXDATA_MASK 0xFFUL /**< Bit mask for I2C_RXDATA */
-#define _I2C_RXDATA_RXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_RXDATA */
-#define I2C_RXDATA_RXDATA_DEFAULT (_I2C_RXDATA_RXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_RXDATA */
-
-/* Bit fields for I2C RXDATAP */
-#define _I2C_RXDATAP_RESETVALUE 0x00000000UL /**< Default value for I2C_RXDATAP */
-#define _I2C_RXDATAP_MASK 0x000000FFUL /**< Mask for I2C_RXDATAP */
-#define _I2C_RXDATAP_RXDATAP_SHIFT 0 /**< Shift value for I2C_RXDATAP */
-#define _I2C_RXDATAP_RXDATAP_MASK 0xFFUL /**< Bit mask for I2C_RXDATAP */
-#define _I2C_RXDATAP_RXDATAP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_RXDATAP */
-#define I2C_RXDATAP_RXDATAP_DEFAULT (_I2C_RXDATAP_RXDATAP_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_RXDATAP */
-
-/* Bit fields for I2C TXDATA */
-#define _I2C_TXDATA_RESETVALUE 0x00000000UL /**< Default value for I2C_TXDATA */
-#define _I2C_TXDATA_MASK 0x000000FFUL /**< Mask for I2C_TXDATA */
-#define _I2C_TXDATA_TXDATA_SHIFT 0 /**< Shift value for I2C_TXDATA */
-#define _I2C_TXDATA_TXDATA_MASK 0xFFUL /**< Bit mask for I2C_TXDATA */
-#define _I2C_TXDATA_TXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_TXDATA */
-#define I2C_TXDATA_TXDATA_DEFAULT (_I2C_TXDATA_TXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_TXDATA */
-
-/* Bit fields for I2C IF */
-#define _I2C_IF_RESETVALUE 0x00000010UL /**< Default value for I2C_IF */
-#define _I2C_IF_MASK 0x0001FFFFUL /**< Mask for I2C_IF */
-#define I2C_IF_START (0x1UL << 0) /**< START condition Interrupt Flag */
-#define _I2C_IF_START_SHIFT 0 /**< Shift value for I2C_START */
-#define _I2C_IF_START_MASK 0x1UL /**< Bit mask for I2C_START */
-#define _I2C_IF_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_START_DEFAULT (_I2C_IF_START_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_RSTART (0x1UL << 1) /**< Repeated START condition Interrupt Flag */
-#define _I2C_IF_RSTART_SHIFT 1 /**< Shift value for I2C_RSTART */
-#define _I2C_IF_RSTART_MASK 0x2UL /**< Bit mask for I2C_RSTART */
-#define _I2C_IF_RSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_RSTART_DEFAULT (_I2C_IF_RSTART_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_ADDR (0x1UL << 2) /**< Address Interrupt Flag */
-#define _I2C_IF_ADDR_SHIFT 2 /**< Shift value for I2C_ADDR */
-#define _I2C_IF_ADDR_MASK 0x4UL /**< Bit mask for I2C_ADDR */
-#define _I2C_IF_ADDR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_ADDR_DEFAULT (_I2C_IF_ADDR_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_TXC (0x1UL << 3) /**< Transfer Completed Interrupt Flag */
-#define _I2C_IF_TXC_SHIFT 3 /**< Shift value for I2C_TXC */
-#define _I2C_IF_TXC_MASK 0x8UL /**< Bit mask for I2C_TXC */
-#define _I2C_IF_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_TXC_DEFAULT (_I2C_IF_TXC_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_TXBL (0x1UL << 4) /**< Transmit Buffer Level Interrupt Flag */
-#define _I2C_IF_TXBL_SHIFT 4 /**< Shift value for I2C_TXBL */
-#define _I2C_IF_TXBL_MASK 0x10UL /**< Bit mask for I2C_TXBL */
-#define _I2C_IF_TXBL_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_TXBL_DEFAULT (_I2C_IF_TXBL_DEFAULT << 4) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_RXDATAV (0x1UL << 5) /**< Receive Data Valid Interrupt Flag */
-#define _I2C_IF_RXDATAV_SHIFT 5 /**< Shift value for I2C_RXDATAV */
-#define _I2C_IF_RXDATAV_MASK 0x20UL /**< Bit mask for I2C_RXDATAV */
-#define _I2C_IF_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_RXDATAV_DEFAULT (_I2C_IF_RXDATAV_DEFAULT << 5) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_ACK (0x1UL << 6) /**< Acknowledge Received Interrupt Flag */
-#define _I2C_IF_ACK_SHIFT 6 /**< Shift value for I2C_ACK */
-#define _I2C_IF_ACK_MASK 0x40UL /**< Bit mask for I2C_ACK */
-#define _I2C_IF_ACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_ACK_DEFAULT (_I2C_IF_ACK_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_NACK (0x1UL << 7) /**< Not Acknowledge Received Interrupt Flag */
-#define _I2C_IF_NACK_SHIFT 7 /**< Shift value for I2C_NACK */
-#define _I2C_IF_NACK_MASK 0x80UL /**< Bit mask for I2C_NACK */
-#define _I2C_IF_NACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_NACK_DEFAULT (_I2C_IF_NACK_DEFAULT << 7) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_MSTOP (0x1UL << 8) /**< Master STOP Condition Interrupt Flag */
-#define _I2C_IF_MSTOP_SHIFT 8 /**< Shift value for I2C_MSTOP */
-#define _I2C_IF_MSTOP_MASK 0x100UL /**< Bit mask for I2C_MSTOP */
-#define _I2C_IF_MSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_MSTOP_DEFAULT (_I2C_IF_MSTOP_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_ARBLOST (0x1UL << 9) /**< Arbitration Lost Interrupt Flag */
-#define _I2C_IF_ARBLOST_SHIFT 9 /**< Shift value for I2C_ARBLOST */
-#define _I2C_IF_ARBLOST_MASK 0x200UL /**< Bit mask for I2C_ARBLOST */
-#define _I2C_IF_ARBLOST_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_ARBLOST_DEFAULT (_I2C_IF_ARBLOST_DEFAULT << 9) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_BUSERR (0x1UL << 10) /**< Bus Error Interrupt Flag */
-#define _I2C_IF_BUSERR_SHIFT 10 /**< Shift value for I2C_BUSERR */
-#define _I2C_IF_BUSERR_MASK 0x400UL /**< Bit mask for I2C_BUSERR */
-#define _I2C_IF_BUSERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_BUSERR_DEFAULT (_I2C_IF_BUSERR_DEFAULT << 10) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_BUSHOLD (0x1UL << 11) /**< Bus Held Interrupt Flag */
-#define _I2C_IF_BUSHOLD_SHIFT 11 /**< Shift value for I2C_BUSHOLD */
-#define _I2C_IF_BUSHOLD_MASK 0x800UL /**< Bit mask for I2C_BUSHOLD */
-#define _I2C_IF_BUSHOLD_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_BUSHOLD_DEFAULT (_I2C_IF_BUSHOLD_DEFAULT << 11) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_TXOF (0x1UL << 12) /**< Transmit Buffer Overflow Interrupt Flag */
-#define _I2C_IF_TXOF_SHIFT 12 /**< Shift value for I2C_TXOF */
-#define _I2C_IF_TXOF_MASK 0x1000UL /**< Bit mask for I2C_TXOF */
-#define _I2C_IF_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_TXOF_DEFAULT (_I2C_IF_TXOF_DEFAULT << 12) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_RXUF (0x1UL << 13) /**< Receive Buffer Underflow Interrupt Flag */
-#define _I2C_IF_RXUF_SHIFT 13 /**< Shift value for I2C_RXUF */
-#define _I2C_IF_RXUF_MASK 0x2000UL /**< Bit mask for I2C_RXUF */
-#define _I2C_IF_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_RXUF_DEFAULT (_I2C_IF_RXUF_DEFAULT << 13) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_BITO (0x1UL << 14) /**< Bus Idle Timeout Interrupt Flag */
-#define _I2C_IF_BITO_SHIFT 14 /**< Shift value for I2C_BITO */
-#define _I2C_IF_BITO_MASK 0x4000UL /**< Bit mask for I2C_BITO */
-#define _I2C_IF_BITO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_BITO_DEFAULT (_I2C_IF_BITO_DEFAULT << 14) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_CLTO (0x1UL << 15) /**< Clock Low Timeout Interrupt Flag */
-#define _I2C_IF_CLTO_SHIFT 15 /**< Shift value for I2C_CLTO */
-#define _I2C_IF_CLTO_MASK 0x8000UL /**< Bit mask for I2C_CLTO */
-#define _I2C_IF_CLTO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_CLTO_DEFAULT (_I2C_IF_CLTO_DEFAULT << 15) /**< Shifted mode DEFAULT for I2C_IF */
-#define I2C_IF_SSTOP (0x1UL << 16) /**< Slave STOP condition Interrupt Flag */
-#define _I2C_IF_SSTOP_SHIFT 16 /**< Shift value for I2C_SSTOP */
-#define _I2C_IF_SSTOP_MASK 0x10000UL /**< Bit mask for I2C_SSTOP */
-#define _I2C_IF_SSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IF */
-#define I2C_IF_SSTOP_DEFAULT (_I2C_IF_SSTOP_DEFAULT << 16) /**< Shifted mode DEFAULT for I2C_IF */
-
-/* Bit fields for I2C IFS */
-#define _I2C_IFS_RESETVALUE 0x00000000UL /**< Default value for I2C_IFS */
-#define _I2C_IFS_MASK 0x0001FFCFUL /**< Mask for I2C_IFS */
-#define I2C_IFS_START (0x1UL << 0) /**< Set START Interrupt Flag */
-#define _I2C_IFS_START_SHIFT 0 /**< Shift value for I2C_START */
-#define _I2C_IFS_START_MASK 0x1UL /**< Bit mask for I2C_START */
-#define _I2C_IFS_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_START_DEFAULT (_I2C_IFS_START_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_RSTART (0x1UL << 1) /**< Set Repeated START Interrupt Flag */
-#define _I2C_IFS_RSTART_SHIFT 1 /**< Shift value for I2C_RSTART */
-#define _I2C_IFS_RSTART_MASK 0x2UL /**< Bit mask for I2C_RSTART */
-#define _I2C_IFS_RSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_RSTART_DEFAULT (_I2C_IFS_RSTART_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_ADDR (0x1UL << 2) /**< Set Address Interrupt Flag */
-#define _I2C_IFS_ADDR_SHIFT 2 /**< Shift value for I2C_ADDR */
-#define _I2C_IFS_ADDR_MASK 0x4UL /**< Bit mask for I2C_ADDR */
-#define _I2C_IFS_ADDR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_ADDR_DEFAULT (_I2C_IFS_ADDR_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_TXC (0x1UL << 3) /**< Set Transfer Completed Interrupt Flag */
-#define _I2C_IFS_TXC_SHIFT 3 /**< Shift value for I2C_TXC */
-#define _I2C_IFS_TXC_MASK 0x8UL /**< Bit mask for I2C_TXC */
-#define _I2C_IFS_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_TXC_DEFAULT (_I2C_IFS_TXC_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_ACK (0x1UL << 6) /**< Set Acknowledge Received Interrupt Flag */
-#define _I2C_IFS_ACK_SHIFT 6 /**< Shift value for I2C_ACK */
-#define _I2C_IFS_ACK_MASK 0x40UL /**< Bit mask for I2C_ACK */
-#define _I2C_IFS_ACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_ACK_DEFAULT (_I2C_IFS_ACK_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_NACK (0x1UL << 7) /**< Set Not Acknowledge Received Interrupt Flag */
-#define _I2C_IFS_NACK_SHIFT 7 /**< Shift value for I2C_NACK */
-#define _I2C_IFS_NACK_MASK 0x80UL /**< Bit mask for I2C_NACK */
-#define _I2C_IFS_NACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_NACK_DEFAULT (_I2C_IFS_NACK_DEFAULT << 7) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_MSTOP (0x1UL << 8) /**< Set MSTOP Interrupt Flag */
-#define _I2C_IFS_MSTOP_SHIFT 8 /**< Shift value for I2C_MSTOP */
-#define _I2C_IFS_MSTOP_MASK 0x100UL /**< Bit mask for I2C_MSTOP */
-#define _I2C_IFS_MSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_MSTOP_DEFAULT (_I2C_IFS_MSTOP_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_ARBLOST (0x1UL << 9) /**< Set Arbitration Lost Interrupt Flag */
-#define _I2C_IFS_ARBLOST_SHIFT 9 /**< Shift value for I2C_ARBLOST */
-#define _I2C_IFS_ARBLOST_MASK 0x200UL /**< Bit mask for I2C_ARBLOST */
-#define _I2C_IFS_ARBLOST_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_ARBLOST_DEFAULT (_I2C_IFS_ARBLOST_DEFAULT << 9) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_BUSERR (0x1UL << 10) /**< Set Bus Error Interrupt Flag */
-#define _I2C_IFS_BUSERR_SHIFT 10 /**< Shift value for I2C_BUSERR */
-#define _I2C_IFS_BUSERR_MASK 0x400UL /**< Bit mask for I2C_BUSERR */
-#define _I2C_IFS_BUSERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_BUSERR_DEFAULT (_I2C_IFS_BUSERR_DEFAULT << 10) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_BUSHOLD (0x1UL << 11) /**< Set Bus Held Interrupt Flag */
-#define _I2C_IFS_BUSHOLD_SHIFT 11 /**< Shift value for I2C_BUSHOLD */
-#define _I2C_IFS_BUSHOLD_MASK 0x800UL /**< Bit mask for I2C_BUSHOLD */
-#define _I2C_IFS_BUSHOLD_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_BUSHOLD_DEFAULT (_I2C_IFS_BUSHOLD_DEFAULT << 11) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_TXOF (0x1UL << 12) /**< Set Transmit Buffer Overflow Interrupt Flag */
-#define _I2C_IFS_TXOF_SHIFT 12 /**< Shift value for I2C_TXOF */
-#define _I2C_IFS_TXOF_MASK 0x1000UL /**< Bit mask for I2C_TXOF */
-#define _I2C_IFS_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_TXOF_DEFAULT (_I2C_IFS_TXOF_DEFAULT << 12) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_RXUF (0x1UL << 13) /**< Set Receive Buffer Underflow Interrupt Flag */
-#define _I2C_IFS_RXUF_SHIFT 13 /**< Shift value for I2C_RXUF */
-#define _I2C_IFS_RXUF_MASK 0x2000UL /**< Bit mask for I2C_RXUF */
-#define _I2C_IFS_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_RXUF_DEFAULT (_I2C_IFS_RXUF_DEFAULT << 13) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_BITO (0x1UL << 14) /**< Set Bus Idle Timeout Interrupt Flag */
-#define _I2C_IFS_BITO_SHIFT 14 /**< Shift value for I2C_BITO */
-#define _I2C_IFS_BITO_MASK 0x4000UL /**< Bit mask for I2C_BITO */
-#define _I2C_IFS_BITO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_BITO_DEFAULT (_I2C_IFS_BITO_DEFAULT << 14) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_CLTO (0x1UL << 15) /**< Set Clock Low Interrupt Flag */
-#define _I2C_IFS_CLTO_SHIFT 15 /**< Shift value for I2C_CLTO */
-#define _I2C_IFS_CLTO_MASK 0x8000UL /**< Bit mask for I2C_CLTO */
-#define _I2C_IFS_CLTO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_CLTO_DEFAULT (_I2C_IFS_CLTO_DEFAULT << 15) /**< Shifted mode DEFAULT for I2C_IFS */
-#define I2C_IFS_SSTOP (0x1UL << 16) /**< Set SSTOP Interrupt Flag */
-#define _I2C_IFS_SSTOP_SHIFT 16 /**< Shift value for I2C_SSTOP */
-#define _I2C_IFS_SSTOP_MASK 0x10000UL /**< Bit mask for I2C_SSTOP */
-#define _I2C_IFS_SSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFS */
-#define I2C_IFS_SSTOP_DEFAULT (_I2C_IFS_SSTOP_DEFAULT << 16) /**< Shifted mode DEFAULT for I2C_IFS */
-
-/* Bit fields for I2C IFC */
-#define _I2C_IFC_RESETVALUE 0x00000000UL /**< Default value for I2C_IFC */
-#define _I2C_IFC_MASK 0x0001FFCFUL /**< Mask for I2C_IFC */
-#define I2C_IFC_START (0x1UL << 0) /**< Clear START Interrupt Flag */
-#define _I2C_IFC_START_SHIFT 0 /**< Shift value for I2C_START */
-#define _I2C_IFC_START_MASK 0x1UL /**< Bit mask for I2C_START */
-#define _I2C_IFC_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_START_DEFAULT (_I2C_IFC_START_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_RSTART (0x1UL << 1) /**< Clear Repeated START Interrupt Flag */
-#define _I2C_IFC_RSTART_SHIFT 1 /**< Shift value for I2C_RSTART */
-#define _I2C_IFC_RSTART_MASK 0x2UL /**< Bit mask for I2C_RSTART */
-#define _I2C_IFC_RSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_RSTART_DEFAULT (_I2C_IFC_RSTART_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_ADDR (0x1UL << 2) /**< Clear Address Interrupt Flag */
-#define _I2C_IFC_ADDR_SHIFT 2 /**< Shift value for I2C_ADDR */
-#define _I2C_IFC_ADDR_MASK 0x4UL /**< Bit mask for I2C_ADDR */
-#define _I2C_IFC_ADDR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_ADDR_DEFAULT (_I2C_IFC_ADDR_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_TXC (0x1UL << 3) /**< Clear Transfer Completed Interrupt Flag */
-#define _I2C_IFC_TXC_SHIFT 3 /**< Shift value for I2C_TXC */
-#define _I2C_IFC_TXC_MASK 0x8UL /**< Bit mask for I2C_TXC */
-#define _I2C_IFC_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_TXC_DEFAULT (_I2C_IFC_TXC_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_ACK (0x1UL << 6) /**< Clear Acknowledge Received Interrupt Flag */
-#define _I2C_IFC_ACK_SHIFT 6 /**< Shift value for I2C_ACK */
-#define _I2C_IFC_ACK_MASK 0x40UL /**< Bit mask for I2C_ACK */
-#define _I2C_IFC_ACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_ACK_DEFAULT (_I2C_IFC_ACK_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_NACK (0x1UL << 7) /**< Clear Not Acknowledge Received Interrupt Flag */
-#define _I2C_IFC_NACK_SHIFT 7 /**< Shift value for I2C_NACK */
-#define _I2C_IFC_NACK_MASK 0x80UL /**< Bit mask for I2C_NACK */
-#define _I2C_IFC_NACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_NACK_DEFAULT (_I2C_IFC_NACK_DEFAULT << 7) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_MSTOP (0x1UL << 8) /**< Clear MSTOP Interrupt Flag */
-#define _I2C_IFC_MSTOP_SHIFT 8 /**< Shift value for I2C_MSTOP */
-#define _I2C_IFC_MSTOP_MASK 0x100UL /**< Bit mask for I2C_MSTOP */
-#define _I2C_IFC_MSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_MSTOP_DEFAULT (_I2C_IFC_MSTOP_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_ARBLOST (0x1UL << 9) /**< Clear Arbitration Lost Interrupt Flag */
-#define _I2C_IFC_ARBLOST_SHIFT 9 /**< Shift value for I2C_ARBLOST */
-#define _I2C_IFC_ARBLOST_MASK 0x200UL /**< Bit mask for I2C_ARBLOST */
-#define _I2C_IFC_ARBLOST_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_ARBLOST_DEFAULT (_I2C_IFC_ARBLOST_DEFAULT << 9) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_BUSERR (0x1UL << 10) /**< Clear Bus Error Interrupt Flag */
-#define _I2C_IFC_BUSERR_SHIFT 10 /**< Shift value for I2C_BUSERR */
-#define _I2C_IFC_BUSERR_MASK 0x400UL /**< Bit mask for I2C_BUSERR */
-#define _I2C_IFC_BUSERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_BUSERR_DEFAULT (_I2C_IFC_BUSERR_DEFAULT << 10) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_BUSHOLD (0x1UL << 11) /**< Clear Bus Held Interrupt Flag */
-#define _I2C_IFC_BUSHOLD_SHIFT 11 /**< Shift value for I2C_BUSHOLD */
-#define _I2C_IFC_BUSHOLD_MASK 0x800UL /**< Bit mask for I2C_BUSHOLD */
-#define _I2C_IFC_BUSHOLD_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_BUSHOLD_DEFAULT (_I2C_IFC_BUSHOLD_DEFAULT << 11) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_TXOF (0x1UL << 12) /**< Clear Transmit Buffer Overflow Interrupt Flag */
-#define _I2C_IFC_TXOF_SHIFT 12 /**< Shift value for I2C_TXOF */
-#define _I2C_IFC_TXOF_MASK 0x1000UL /**< Bit mask for I2C_TXOF */
-#define _I2C_IFC_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_TXOF_DEFAULT (_I2C_IFC_TXOF_DEFAULT << 12) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_RXUF (0x1UL << 13) /**< Clear Receive Buffer Underflow Interrupt Flag */
-#define _I2C_IFC_RXUF_SHIFT 13 /**< Shift value for I2C_RXUF */
-#define _I2C_IFC_RXUF_MASK 0x2000UL /**< Bit mask for I2C_RXUF */
-#define _I2C_IFC_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_RXUF_DEFAULT (_I2C_IFC_RXUF_DEFAULT << 13) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_BITO (0x1UL << 14) /**< Clear Bus Idle Timeout Interrupt Flag */
-#define _I2C_IFC_BITO_SHIFT 14 /**< Shift value for I2C_BITO */
-#define _I2C_IFC_BITO_MASK 0x4000UL /**< Bit mask for I2C_BITO */
-#define _I2C_IFC_BITO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_BITO_DEFAULT (_I2C_IFC_BITO_DEFAULT << 14) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_CLTO (0x1UL << 15) /**< Clear Clock Low Interrupt Flag */
-#define _I2C_IFC_CLTO_SHIFT 15 /**< Shift value for I2C_CLTO */
-#define _I2C_IFC_CLTO_MASK 0x8000UL /**< Bit mask for I2C_CLTO */
-#define _I2C_IFC_CLTO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_CLTO_DEFAULT (_I2C_IFC_CLTO_DEFAULT << 15) /**< Shifted mode DEFAULT for I2C_IFC */
-#define I2C_IFC_SSTOP (0x1UL << 16) /**< Clear SSTOP Interrupt Flag */
-#define _I2C_IFC_SSTOP_SHIFT 16 /**< Shift value for I2C_SSTOP */
-#define _I2C_IFC_SSTOP_MASK 0x10000UL /**< Bit mask for I2C_SSTOP */
-#define _I2C_IFC_SSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IFC */
-#define I2C_IFC_SSTOP_DEFAULT (_I2C_IFC_SSTOP_DEFAULT << 16) /**< Shifted mode DEFAULT for I2C_IFC */
-
-/* Bit fields for I2C IEN */
-#define _I2C_IEN_RESETVALUE 0x00000000UL /**< Default value for I2C_IEN */
-#define _I2C_IEN_MASK 0x0001FFFFUL /**< Mask for I2C_IEN */
-#define I2C_IEN_START (0x1UL << 0) /**< START Condition Interrupt Enable */
-#define _I2C_IEN_START_SHIFT 0 /**< Shift value for I2C_START */
-#define _I2C_IEN_START_MASK 0x1UL /**< Bit mask for I2C_START */
-#define _I2C_IEN_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_START_DEFAULT (_I2C_IEN_START_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_RSTART (0x1UL << 1) /**< Repeated START condition Interrupt Enable */
-#define _I2C_IEN_RSTART_SHIFT 1 /**< Shift value for I2C_RSTART */
-#define _I2C_IEN_RSTART_MASK 0x2UL /**< Bit mask for I2C_RSTART */
-#define _I2C_IEN_RSTART_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_RSTART_DEFAULT (_I2C_IEN_RSTART_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_ADDR (0x1UL << 2) /**< Address Interrupt Enable */
-#define _I2C_IEN_ADDR_SHIFT 2 /**< Shift value for I2C_ADDR */
-#define _I2C_IEN_ADDR_MASK 0x4UL /**< Bit mask for I2C_ADDR */
-#define _I2C_IEN_ADDR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_ADDR_DEFAULT (_I2C_IEN_ADDR_DEFAULT << 2) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_TXC (0x1UL << 3) /**< Transfer Completed Interrupt Enable */
-#define _I2C_IEN_TXC_SHIFT 3 /**< Shift value for I2C_TXC */
-#define _I2C_IEN_TXC_MASK 0x8UL /**< Bit mask for I2C_TXC */
-#define _I2C_IEN_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_TXC_DEFAULT (_I2C_IEN_TXC_DEFAULT << 3) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_TXBL (0x1UL << 4) /**< Transmit Buffer level Interrupt Enable */
-#define _I2C_IEN_TXBL_SHIFT 4 /**< Shift value for I2C_TXBL */
-#define _I2C_IEN_TXBL_MASK 0x10UL /**< Bit mask for I2C_TXBL */
-#define _I2C_IEN_TXBL_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_TXBL_DEFAULT (_I2C_IEN_TXBL_DEFAULT << 4) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_RXDATAV (0x1UL << 5) /**< Receive Data Valid Interrupt Enable */
-#define _I2C_IEN_RXDATAV_SHIFT 5 /**< Shift value for I2C_RXDATAV */
-#define _I2C_IEN_RXDATAV_MASK 0x20UL /**< Bit mask for I2C_RXDATAV */
-#define _I2C_IEN_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_RXDATAV_DEFAULT (_I2C_IEN_RXDATAV_DEFAULT << 5) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_ACK (0x1UL << 6) /**< Acknowledge Received Interrupt Enable */
-#define _I2C_IEN_ACK_SHIFT 6 /**< Shift value for I2C_ACK */
-#define _I2C_IEN_ACK_MASK 0x40UL /**< Bit mask for I2C_ACK */
-#define _I2C_IEN_ACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_ACK_DEFAULT (_I2C_IEN_ACK_DEFAULT << 6) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_NACK (0x1UL << 7) /**< Not Acknowledge Received Interrupt Enable */
-#define _I2C_IEN_NACK_SHIFT 7 /**< Shift value for I2C_NACK */
-#define _I2C_IEN_NACK_MASK 0x80UL /**< Bit mask for I2C_NACK */
-#define _I2C_IEN_NACK_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_NACK_DEFAULT (_I2C_IEN_NACK_DEFAULT << 7) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_MSTOP (0x1UL << 8) /**< MSTOP Interrupt Enable */
-#define _I2C_IEN_MSTOP_SHIFT 8 /**< Shift value for I2C_MSTOP */
-#define _I2C_IEN_MSTOP_MASK 0x100UL /**< Bit mask for I2C_MSTOP */
-#define _I2C_IEN_MSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_MSTOP_DEFAULT (_I2C_IEN_MSTOP_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_ARBLOST (0x1UL << 9) /**< Arbitration Lost Interrupt Enable */
-#define _I2C_IEN_ARBLOST_SHIFT 9 /**< Shift value for I2C_ARBLOST */
-#define _I2C_IEN_ARBLOST_MASK 0x200UL /**< Bit mask for I2C_ARBLOST */
-#define _I2C_IEN_ARBLOST_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_ARBLOST_DEFAULT (_I2C_IEN_ARBLOST_DEFAULT << 9) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_BUSERR (0x1UL << 10) /**< Bus Error Interrupt Enable */
-#define _I2C_IEN_BUSERR_SHIFT 10 /**< Shift value for I2C_BUSERR */
-#define _I2C_IEN_BUSERR_MASK 0x400UL /**< Bit mask for I2C_BUSERR */
-#define _I2C_IEN_BUSERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_BUSERR_DEFAULT (_I2C_IEN_BUSERR_DEFAULT << 10) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_BUSHOLD (0x1UL << 11) /**< Bus Held Interrupt Enable */
-#define _I2C_IEN_BUSHOLD_SHIFT 11 /**< Shift value for I2C_BUSHOLD */
-#define _I2C_IEN_BUSHOLD_MASK 0x800UL /**< Bit mask for I2C_BUSHOLD */
-#define _I2C_IEN_BUSHOLD_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_BUSHOLD_DEFAULT (_I2C_IEN_BUSHOLD_DEFAULT << 11) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_TXOF (0x1UL << 12) /**< Transmit Buffer Overflow Interrupt Enable */
-#define _I2C_IEN_TXOF_SHIFT 12 /**< Shift value for I2C_TXOF */
-#define _I2C_IEN_TXOF_MASK 0x1000UL /**< Bit mask for I2C_TXOF */
-#define _I2C_IEN_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_TXOF_DEFAULT (_I2C_IEN_TXOF_DEFAULT << 12) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_RXUF (0x1UL << 13) /**< Receive Buffer Underflow Interrupt Enable */
-#define _I2C_IEN_RXUF_SHIFT 13 /**< Shift value for I2C_RXUF */
-#define _I2C_IEN_RXUF_MASK 0x2000UL /**< Bit mask for I2C_RXUF */
-#define _I2C_IEN_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_RXUF_DEFAULT (_I2C_IEN_RXUF_DEFAULT << 13) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_BITO (0x1UL << 14) /**< Bus Idle Timeout Interrupt Enable */
-#define _I2C_IEN_BITO_SHIFT 14 /**< Shift value for I2C_BITO */
-#define _I2C_IEN_BITO_MASK 0x4000UL /**< Bit mask for I2C_BITO */
-#define _I2C_IEN_BITO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_BITO_DEFAULT (_I2C_IEN_BITO_DEFAULT << 14) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_CLTO (0x1UL << 15) /**< Clock Low Interrupt Enable */
-#define _I2C_IEN_CLTO_SHIFT 15 /**< Shift value for I2C_CLTO */
-#define _I2C_IEN_CLTO_MASK 0x8000UL /**< Bit mask for I2C_CLTO */
-#define _I2C_IEN_CLTO_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_CLTO_DEFAULT (_I2C_IEN_CLTO_DEFAULT << 15) /**< Shifted mode DEFAULT for I2C_IEN */
-#define I2C_IEN_SSTOP (0x1UL << 16) /**< SSTOP Interrupt Enable */
-#define _I2C_IEN_SSTOP_SHIFT 16 /**< Shift value for I2C_SSTOP */
-#define _I2C_IEN_SSTOP_MASK 0x10000UL /**< Bit mask for I2C_SSTOP */
-#define _I2C_IEN_SSTOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_IEN */
-#define I2C_IEN_SSTOP_DEFAULT (_I2C_IEN_SSTOP_DEFAULT << 16) /**< Shifted mode DEFAULT for I2C_IEN */
-
-/* Bit fields for I2C ROUTE */
-#define _I2C_ROUTE_RESETVALUE 0x00000000UL /**< Default value for I2C_ROUTE */
-#define _I2C_ROUTE_MASK 0x00000703UL /**< Mask for I2C_ROUTE */
-#define I2C_ROUTE_SDAPEN (0x1UL << 0) /**< SDA Pin Enable */
-#define _I2C_ROUTE_SDAPEN_SHIFT 0 /**< Shift value for I2C_SDAPEN */
-#define _I2C_ROUTE_SDAPEN_MASK 0x1UL /**< Bit mask for I2C_SDAPEN */
-#define _I2C_ROUTE_SDAPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_ROUTE */
-#define I2C_ROUTE_SDAPEN_DEFAULT (_I2C_ROUTE_SDAPEN_DEFAULT << 0) /**< Shifted mode DEFAULT for I2C_ROUTE */
-#define I2C_ROUTE_SCLPEN (0x1UL << 1) /**< SCL Pin Enable */
-#define _I2C_ROUTE_SCLPEN_SHIFT 1 /**< Shift value for I2C_SCLPEN */
-#define _I2C_ROUTE_SCLPEN_MASK 0x2UL /**< Bit mask for I2C_SCLPEN */
-#define _I2C_ROUTE_SCLPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_ROUTE */
-#define I2C_ROUTE_SCLPEN_DEFAULT (_I2C_ROUTE_SCLPEN_DEFAULT << 1) /**< Shifted mode DEFAULT for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_SHIFT 8 /**< Shift value for I2C_LOCATION */
-#define _I2C_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for I2C_LOCATION */
-#define _I2C_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_LOC3 0x00000003UL /**< Mode LOC3 for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_LOC4 0x00000004UL /**< Mode LOC4 for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_LOC5 0x00000005UL /**< Mode LOC5 for I2C_ROUTE */
-#define _I2C_ROUTE_LOCATION_LOC6 0x00000006UL /**< Mode LOC6 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC0 (_I2C_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_DEFAULT (_I2C_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC1 (_I2C_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC2 (_I2C_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC3 (_I2C_ROUTE_LOCATION_LOC3 << 8) /**< Shifted mode LOC3 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC4 (_I2C_ROUTE_LOCATION_LOC4 << 8) /**< Shifted mode LOC4 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC5 (_I2C_ROUTE_LOCATION_LOC5 << 8) /**< Shifted mode LOC5 for I2C_ROUTE */
-#define I2C_ROUTE_LOCATION_LOC6 (_I2C_ROUTE_LOCATION_LOC6 << 8) /**< Shifted mode LOC6 for I2C_ROUTE */
-
-/** @} End of group EFM32ZG_I2C */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_idac.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_idac.h
deleted file mode 100644
index 8b0bcf9f07..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_idac.h
+++ /dev/null
@@ -1,151 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_IDAC register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_IDAC
- * @{
- * @brief EFM32ZG_IDAC Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CURPROG; /**< Current Programming Register */
- __IOM uint32_t CAL; /**< Calibration Register */
- __IOM uint32_t DUTYCONFIG; /**< Duty Cycle Configauration Register */
-} IDAC_TypeDef; /** IDAC Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_IDAC_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for IDAC CTRL */
-#define _IDAC_CTRL_RESETVALUE 0x00000000UL /**< Default value for IDAC_CTRL */
-#define _IDAC_CTRL_MASK 0x0034001FUL /**< Mask for IDAC_CTRL */
-#define IDAC_CTRL_EN (0x1UL << 0) /**< Current DAC Enable */
-#define _IDAC_CTRL_EN_SHIFT 0 /**< Shift value for IDAC_EN */
-#define _IDAC_CTRL_EN_MASK 0x1UL /**< Bit mask for IDAC_EN */
-#define _IDAC_CTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_EN_DEFAULT (_IDAC_CTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_CURSINK (0x1UL << 1) /**< Current Sink Enable */
-#define _IDAC_CTRL_CURSINK_SHIFT 1 /**< Shift value for IDAC_CURSINK */
-#define _IDAC_CTRL_CURSINK_MASK 0x2UL /**< Bit mask for IDAC_CURSINK */
-#define _IDAC_CTRL_CURSINK_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_CURSINK_DEFAULT (_IDAC_CTRL_CURSINK_DEFAULT << 1) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_MINOUTTRANS (0x1UL << 2) /**< Minimum Output Transition Enable */
-#define _IDAC_CTRL_MINOUTTRANS_SHIFT 2 /**< Shift value for IDAC_MINOUTTRANS */
-#define _IDAC_CTRL_MINOUTTRANS_MASK 0x4UL /**< Bit mask for IDAC_MINOUTTRANS */
-#define _IDAC_CTRL_MINOUTTRANS_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_MINOUTTRANS_DEFAULT (_IDAC_CTRL_MINOUTTRANS_DEFAULT << 2) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_OUTEN (0x1UL << 3) /**< Output Enable */
-#define _IDAC_CTRL_OUTEN_SHIFT 3 /**< Shift value for IDAC_OUTEN */
-#define _IDAC_CTRL_OUTEN_MASK 0x8UL /**< Bit mask for IDAC_OUTEN */
-#define _IDAC_CTRL_OUTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_OUTEN_DEFAULT (_IDAC_CTRL_OUTEN_DEFAULT << 3) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_OUTMODE (0x1UL << 4) /**< Output Modes */
-#define _IDAC_CTRL_OUTMODE_SHIFT 4 /**< Shift value for IDAC_OUTMODE */
-#define _IDAC_CTRL_OUTMODE_MASK 0x10UL /**< Bit mask for IDAC_OUTMODE */
-#define _IDAC_CTRL_OUTMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define _IDAC_CTRL_OUTMODE_PIN 0x00000000UL /**< Mode PIN for IDAC_CTRL */
-#define _IDAC_CTRL_OUTMODE_ADC 0x00000001UL /**< Mode ADC for IDAC_CTRL */
-#define IDAC_CTRL_OUTMODE_DEFAULT (_IDAC_CTRL_OUTMODE_DEFAULT << 4) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_OUTMODE_PIN (_IDAC_CTRL_OUTMODE_PIN << 4) /**< Shifted mode PIN for IDAC_CTRL */
-#define IDAC_CTRL_OUTMODE_ADC (_IDAC_CTRL_OUTMODE_ADC << 4) /**< Shifted mode ADC for IDAC_CTRL */
-#define IDAC_CTRL_OUTENPRS (0x1UL << 18) /**< PRS Controlled Output Enable */
-#define _IDAC_CTRL_OUTENPRS_SHIFT 18 /**< Shift value for IDAC_OUTENPRS */
-#define _IDAC_CTRL_OUTENPRS_MASK 0x40000UL /**< Bit mask for IDAC_OUTENPRS */
-#define _IDAC_CTRL_OUTENPRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_OUTENPRS_DEFAULT (_IDAC_CTRL_OUTENPRS_DEFAULT << 18) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define _IDAC_CTRL_PRSSEL_SHIFT 20 /**< Shift value for IDAC_PRSSEL */
-#define _IDAC_CTRL_PRSSEL_MASK 0x300000UL /**< Bit mask for IDAC_PRSSEL */
-#define _IDAC_CTRL_PRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CTRL */
-#define _IDAC_CTRL_PRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for IDAC_CTRL */
-#define _IDAC_CTRL_PRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for IDAC_CTRL */
-#define _IDAC_CTRL_PRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for IDAC_CTRL */
-#define _IDAC_CTRL_PRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for IDAC_CTRL */
-#define IDAC_CTRL_PRSSEL_DEFAULT (_IDAC_CTRL_PRSSEL_DEFAULT << 20) /**< Shifted mode DEFAULT for IDAC_CTRL */
-#define IDAC_CTRL_PRSSEL_PRSCH0 (_IDAC_CTRL_PRSSEL_PRSCH0 << 20) /**< Shifted mode PRSCH0 for IDAC_CTRL */
-#define IDAC_CTRL_PRSSEL_PRSCH1 (_IDAC_CTRL_PRSSEL_PRSCH1 << 20) /**< Shifted mode PRSCH1 for IDAC_CTRL */
-#define IDAC_CTRL_PRSSEL_PRSCH2 (_IDAC_CTRL_PRSSEL_PRSCH2 << 20) /**< Shifted mode PRSCH2 for IDAC_CTRL */
-#define IDAC_CTRL_PRSSEL_PRSCH3 (_IDAC_CTRL_PRSSEL_PRSCH3 << 20) /**< Shifted mode PRSCH3 for IDAC_CTRL */
-
-/* Bit fields for IDAC CURPROG */
-#define _IDAC_CURPROG_RESETVALUE 0x00000000UL /**< Default value for IDAC_CURPROG */
-#define _IDAC_CURPROG_MASK 0x00001F03UL /**< Mask for IDAC_CURPROG */
-#define _IDAC_CURPROG_RANGESEL_SHIFT 0 /**< Shift value for IDAC_RANGESEL */
-#define _IDAC_CURPROG_RANGESEL_MASK 0x3UL /**< Bit mask for IDAC_RANGESEL */
-#define _IDAC_CURPROG_RANGESEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CURPROG */
-#define _IDAC_CURPROG_RANGESEL_RANGE0 0x00000000UL /**< Mode RANGE0 for IDAC_CURPROG */
-#define _IDAC_CURPROG_RANGESEL_RANGE1 0x00000001UL /**< Mode RANGE1 for IDAC_CURPROG */
-#define _IDAC_CURPROG_RANGESEL_RANGE2 0x00000002UL /**< Mode RANGE2 for IDAC_CURPROG */
-#define _IDAC_CURPROG_RANGESEL_RANGE3 0x00000003UL /**< Mode RANGE3 for IDAC_CURPROG */
-#define IDAC_CURPROG_RANGESEL_DEFAULT (_IDAC_CURPROG_RANGESEL_DEFAULT << 0) /**< Shifted mode DEFAULT for IDAC_CURPROG */
-#define IDAC_CURPROG_RANGESEL_RANGE0 (_IDAC_CURPROG_RANGESEL_RANGE0 << 0) /**< Shifted mode RANGE0 for IDAC_CURPROG */
-#define IDAC_CURPROG_RANGESEL_RANGE1 (_IDAC_CURPROG_RANGESEL_RANGE1 << 0) /**< Shifted mode RANGE1 for IDAC_CURPROG */
-#define IDAC_CURPROG_RANGESEL_RANGE2 (_IDAC_CURPROG_RANGESEL_RANGE2 << 0) /**< Shifted mode RANGE2 for IDAC_CURPROG */
-#define IDAC_CURPROG_RANGESEL_RANGE3 (_IDAC_CURPROG_RANGESEL_RANGE3 << 0) /**< Shifted mode RANGE3 for IDAC_CURPROG */
-#define _IDAC_CURPROG_STEPSEL_SHIFT 8 /**< Shift value for IDAC_STEPSEL */
-#define _IDAC_CURPROG_STEPSEL_MASK 0x1F00UL /**< Bit mask for IDAC_STEPSEL */
-#define _IDAC_CURPROG_STEPSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CURPROG */
-#define IDAC_CURPROG_STEPSEL_DEFAULT (_IDAC_CURPROG_STEPSEL_DEFAULT << 8) /**< Shifted mode DEFAULT for IDAC_CURPROG */
-
-/* Bit fields for IDAC CAL */
-#define _IDAC_CAL_RESETVALUE 0x00000000UL /**< Default value for IDAC_CAL */
-#define _IDAC_CAL_MASK 0x0000007FUL /**< Mask for IDAC_CAL */
-#define _IDAC_CAL_TUNING_SHIFT 0 /**< Shift value for IDAC_TUNING */
-#define _IDAC_CAL_TUNING_MASK 0x7FUL /**< Bit mask for IDAC_TUNING */
-#define _IDAC_CAL_TUNING_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_CAL */
-#define IDAC_CAL_TUNING_DEFAULT (_IDAC_CAL_TUNING_DEFAULT << 0) /**< Shifted mode DEFAULT for IDAC_CAL */
-
-/* Bit fields for IDAC DUTYCONFIG */
-#define _IDAC_DUTYCONFIG_RESETVALUE 0x00000000UL /**< Default value for IDAC_DUTYCONFIG */
-#define _IDAC_DUTYCONFIG_MASK 0x00000003UL /**< Mask for IDAC_DUTYCONFIG */
-#define IDAC_DUTYCONFIG_DUTYCYCLEEN (0x1UL << 0) /**< Duty Cycle Enable. */
-#define _IDAC_DUTYCONFIG_DUTYCYCLEEN_SHIFT 0 /**< Shift value for IDAC_DUTYCYCLEEN */
-#define _IDAC_DUTYCONFIG_DUTYCYCLEEN_MASK 0x1UL /**< Bit mask for IDAC_DUTYCYCLEEN */
-#define _IDAC_DUTYCONFIG_DUTYCYCLEEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_DUTYCONFIG */
-#define IDAC_DUTYCONFIG_DUTYCYCLEEN_DEFAULT (_IDAC_DUTYCONFIG_DUTYCYCLEEN_DEFAULT << 0) /**< Shifted mode DEFAULT for IDAC_DUTYCONFIG */
-#define IDAC_DUTYCONFIG_EM2DUTYCYCLEDIS (0x1UL << 1) /**< EM2/EM3 Duty Cycle Disable. */
-#define _IDAC_DUTYCONFIG_EM2DUTYCYCLEDIS_SHIFT 1 /**< Shift value for IDAC_EM2DUTYCYCLEDIS */
-#define _IDAC_DUTYCONFIG_EM2DUTYCYCLEDIS_MASK 0x2UL /**< Bit mask for IDAC_EM2DUTYCYCLEDIS */
-#define _IDAC_DUTYCONFIG_EM2DUTYCYCLEDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for IDAC_DUTYCONFIG */
-#define IDAC_DUTYCONFIG_EM2DUTYCYCLEDIS_DEFAULT (_IDAC_DUTYCONFIG_EM2DUTYCYCLEDIS_DEFAULT << 1) /**< Shifted mode DEFAULT for IDAC_DUTYCONFIG */
-
-/** @} End of group EFM32ZG_IDAC */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_leuart.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_leuart.h
deleted file mode 100644
index b65ecadf74..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_leuart.h
+++ /dev/null
@@ -1,690 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_LEUART register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_LEUART
- * @{
- * @brief EFM32ZG_LEUART Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t CLKDIV; /**< Clock Control Register */
- __IOM uint32_t STARTFRAME; /**< Start Frame Register */
- __IOM uint32_t SIGFRAME; /**< Signal Frame Register */
- __IM uint32_t RXDATAX; /**< Receive Buffer Data Extended Register */
- __IM uint32_t RXDATA; /**< Receive Buffer Data Register */
- __IM uint32_t RXDATAXP; /**< Receive Buffer Data Extended Peek Register */
- __IOM uint32_t TXDATAX; /**< Transmit Buffer Data Extended Register */
- __IOM uint32_t TXDATA; /**< Transmit Buffer Data Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t PULSECTRL; /**< Pulse Control Register */
-
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
-
- uint32_t RESERVED0[3U]; /**< Reserved for future use **/
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- uint32_t RESERVED1[21U]; /**< Reserved for future use **/
- __IOM uint32_t INPUT; /**< LEUART Input Register */
-} LEUART_TypeDef; /** LEUART Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_LEUART_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for LEUART CTRL */
-#define _LEUART_CTRL_RESETVALUE 0x00000000UL /**< Default value for LEUART_CTRL */
-#define _LEUART_CTRL_MASK 0x0000FFFFUL /**< Mask for LEUART_CTRL */
-#define LEUART_CTRL_AUTOTRI (0x1UL << 0) /**< Automatic Transmitter Tristate */
-#define _LEUART_CTRL_AUTOTRI_SHIFT 0 /**< Shift value for LEUART_AUTOTRI */
-#define _LEUART_CTRL_AUTOTRI_MASK 0x1UL /**< Bit mask for LEUART_AUTOTRI */
-#define _LEUART_CTRL_AUTOTRI_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_AUTOTRI_DEFAULT (_LEUART_CTRL_AUTOTRI_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_DATABITS (0x1UL << 1) /**< Data-Bit Mode */
-#define _LEUART_CTRL_DATABITS_SHIFT 1 /**< Shift value for LEUART_DATABITS */
-#define _LEUART_CTRL_DATABITS_MASK 0x2UL /**< Bit mask for LEUART_DATABITS */
-#define _LEUART_CTRL_DATABITS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define _LEUART_CTRL_DATABITS_EIGHT 0x00000000UL /**< Mode EIGHT for LEUART_CTRL */
-#define _LEUART_CTRL_DATABITS_NINE 0x00000001UL /**< Mode NINE for LEUART_CTRL */
-#define LEUART_CTRL_DATABITS_DEFAULT (_LEUART_CTRL_DATABITS_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_DATABITS_EIGHT (_LEUART_CTRL_DATABITS_EIGHT << 1) /**< Shifted mode EIGHT for LEUART_CTRL */
-#define LEUART_CTRL_DATABITS_NINE (_LEUART_CTRL_DATABITS_NINE << 1) /**< Shifted mode NINE for LEUART_CTRL */
-#define _LEUART_CTRL_PARITY_SHIFT 2 /**< Shift value for LEUART_PARITY */
-#define _LEUART_CTRL_PARITY_MASK 0xCUL /**< Bit mask for LEUART_PARITY */
-#define _LEUART_CTRL_PARITY_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define _LEUART_CTRL_PARITY_NONE 0x00000000UL /**< Mode NONE for LEUART_CTRL */
-#define _LEUART_CTRL_PARITY_EVEN 0x00000002UL /**< Mode EVEN for LEUART_CTRL */
-#define _LEUART_CTRL_PARITY_ODD 0x00000003UL /**< Mode ODD for LEUART_CTRL */
-#define LEUART_CTRL_PARITY_DEFAULT (_LEUART_CTRL_PARITY_DEFAULT << 2) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_PARITY_NONE (_LEUART_CTRL_PARITY_NONE << 2) /**< Shifted mode NONE for LEUART_CTRL */
-#define LEUART_CTRL_PARITY_EVEN (_LEUART_CTRL_PARITY_EVEN << 2) /**< Shifted mode EVEN for LEUART_CTRL */
-#define LEUART_CTRL_PARITY_ODD (_LEUART_CTRL_PARITY_ODD << 2) /**< Shifted mode ODD for LEUART_CTRL */
-#define LEUART_CTRL_STOPBITS (0x1UL << 4) /**< Stop-Bit Mode */
-#define _LEUART_CTRL_STOPBITS_SHIFT 4 /**< Shift value for LEUART_STOPBITS */
-#define _LEUART_CTRL_STOPBITS_MASK 0x10UL /**< Bit mask for LEUART_STOPBITS */
-#define _LEUART_CTRL_STOPBITS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define _LEUART_CTRL_STOPBITS_ONE 0x00000000UL /**< Mode ONE for LEUART_CTRL */
-#define _LEUART_CTRL_STOPBITS_TWO 0x00000001UL /**< Mode TWO for LEUART_CTRL */
-#define LEUART_CTRL_STOPBITS_DEFAULT (_LEUART_CTRL_STOPBITS_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_STOPBITS_ONE (_LEUART_CTRL_STOPBITS_ONE << 4) /**< Shifted mode ONE for LEUART_CTRL */
-#define LEUART_CTRL_STOPBITS_TWO (_LEUART_CTRL_STOPBITS_TWO << 4) /**< Shifted mode TWO for LEUART_CTRL */
-#define LEUART_CTRL_INV (0x1UL << 5) /**< Invert Input And Output */
-#define _LEUART_CTRL_INV_SHIFT 5 /**< Shift value for LEUART_INV */
-#define _LEUART_CTRL_INV_MASK 0x20UL /**< Bit mask for LEUART_INV */
-#define _LEUART_CTRL_INV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_INV_DEFAULT (_LEUART_CTRL_INV_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_ERRSDMA (0x1UL << 6) /**< Clear RX DMA On Error */
-#define _LEUART_CTRL_ERRSDMA_SHIFT 6 /**< Shift value for LEUART_ERRSDMA */
-#define _LEUART_CTRL_ERRSDMA_MASK 0x40UL /**< Bit mask for LEUART_ERRSDMA */
-#define _LEUART_CTRL_ERRSDMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_ERRSDMA_DEFAULT (_LEUART_CTRL_ERRSDMA_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_LOOPBK (0x1UL << 7) /**< Loopback Enable */
-#define _LEUART_CTRL_LOOPBK_SHIFT 7 /**< Shift value for LEUART_LOOPBK */
-#define _LEUART_CTRL_LOOPBK_MASK 0x80UL /**< Bit mask for LEUART_LOOPBK */
-#define _LEUART_CTRL_LOOPBK_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_LOOPBK_DEFAULT (_LEUART_CTRL_LOOPBK_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_SFUBRX (0x1UL << 8) /**< Start-Frame UnBlock RX */
-#define _LEUART_CTRL_SFUBRX_SHIFT 8 /**< Shift value for LEUART_SFUBRX */
-#define _LEUART_CTRL_SFUBRX_MASK 0x100UL /**< Bit mask for LEUART_SFUBRX */
-#define _LEUART_CTRL_SFUBRX_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_SFUBRX_DEFAULT (_LEUART_CTRL_SFUBRX_DEFAULT << 8) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_MPM (0x1UL << 9) /**< Multi-Processor Mode */
-#define _LEUART_CTRL_MPM_SHIFT 9 /**< Shift value for LEUART_MPM */
-#define _LEUART_CTRL_MPM_MASK 0x200UL /**< Bit mask for LEUART_MPM */
-#define _LEUART_CTRL_MPM_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_MPM_DEFAULT (_LEUART_CTRL_MPM_DEFAULT << 9) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_MPAB (0x1UL << 10) /**< Multi-Processor Address-Bit */
-#define _LEUART_CTRL_MPAB_SHIFT 10 /**< Shift value for LEUART_MPAB */
-#define _LEUART_CTRL_MPAB_MASK 0x400UL /**< Bit mask for LEUART_MPAB */
-#define _LEUART_CTRL_MPAB_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_MPAB_DEFAULT (_LEUART_CTRL_MPAB_DEFAULT << 10) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_BIT8DV (0x1UL << 11) /**< Bit 8 Default Value */
-#define _LEUART_CTRL_BIT8DV_SHIFT 11 /**< Shift value for LEUART_BIT8DV */
-#define _LEUART_CTRL_BIT8DV_MASK 0x800UL /**< Bit mask for LEUART_BIT8DV */
-#define _LEUART_CTRL_BIT8DV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_BIT8DV_DEFAULT (_LEUART_CTRL_BIT8DV_DEFAULT << 11) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_RXDMAWU (0x1UL << 12) /**< RX DMA Wakeup */
-#define _LEUART_CTRL_RXDMAWU_SHIFT 12 /**< Shift value for LEUART_RXDMAWU */
-#define _LEUART_CTRL_RXDMAWU_MASK 0x1000UL /**< Bit mask for LEUART_RXDMAWU */
-#define _LEUART_CTRL_RXDMAWU_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_RXDMAWU_DEFAULT (_LEUART_CTRL_RXDMAWU_DEFAULT << 12) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_TXDMAWU (0x1UL << 13) /**< TX DMA Wakeup */
-#define _LEUART_CTRL_TXDMAWU_SHIFT 13 /**< Shift value for LEUART_TXDMAWU */
-#define _LEUART_CTRL_TXDMAWU_MASK 0x2000UL /**< Bit mask for LEUART_TXDMAWU */
-#define _LEUART_CTRL_TXDMAWU_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_TXDMAWU_DEFAULT (_LEUART_CTRL_TXDMAWU_DEFAULT << 13) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define _LEUART_CTRL_TXDELAY_SHIFT 14 /**< Shift value for LEUART_TXDELAY */
-#define _LEUART_CTRL_TXDELAY_MASK 0xC000UL /**< Bit mask for LEUART_TXDELAY */
-#define _LEUART_CTRL_TXDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CTRL */
-#define _LEUART_CTRL_TXDELAY_NONE 0x00000000UL /**< Mode NONE for LEUART_CTRL */
-#define _LEUART_CTRL_TXDELAY_SINGLE 0x00000001UL /**< Mode SINGLE for LEUART_CTRL */
-#define _LEUART_CTRL_TXDELAY_DOUBLE 0x00000002UL /**< Mode DOUBLE for LEUART_CTRL */
-#define _LEUART_CTRL_TXDELAY_TRIPLE 0x00000003UL /**< Mode TRIPLE for LEUART_CTRL */
-#define LEUART_CTRL_TXDELAY_DEFAULT (_LEUART_CTRL_TXDELAY_DEFAULT << 14) /**< Shifted mode DEFAULT for LEUART_CTRL */
-#define LEUART_CTRL_TXDELAY_NONE (_LEUART_CTRL_TXDELAY_NONE << 14) /**< Shifted mode NONE for LEUART_CTRL */
-#define LEUART_CTRL_TXDELAY_SINGLE (_LEUART_CTRL_TXDELAY_SINGLE << 14) /**< Shifted mode SINGLE for LEUART_CTRL */
-#define LEUART_CTRL_TXDELAY_DOUBLE (_LEUART_CTRL_TXDELAY_DOUBLE << 14) /**< Shifted mode DOUBLE for LEUART_CTRL */
-#define LEUART_CTRL_TXDELAY_TRIPLE (_LEUART_CTRL_TXDELAY_TRIPLE << 14) /**< Shifted mode TRIPLE for LEUART_CTRL */
-
-/* Bit fields for LEUART CMD */
-#define _LEUART_CMD_RESETVALUE 0x00000000UL /**< Default value for LEUART_CMD */
-#define _LEUART_CMD_MASK 0x000000FFUL /**< Mask for LEUART_CMD */
-#define LEUART_CMD_RXEN (0x1UL << 0) /**< Receiver Enable */
-#define _LEUART_CMD_RXEN_SHIFT 0 /**< Shift value for LEUART_RXEN */
-#define _LEUART_CMD_RXEN_MASK 0x1UL /**< Bit mask for LEUART_RXEN */
-#define _LEUART_CMD_RXEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXEN_DEFAULT (_LEUART_CMD_RXEN_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXDIS (0x1UL << 1) /**< Receiver Disable */
-#define _LEUART_CMD_RXDIS_SHIFT 1 /**< Shift value for LEUART_RXDIS */
-#define _LEUART_CMD_RXDIS_MASK 0x2UL /**< Bit mask for LEUART_RXDIS */
-#define _LEUART_CMD_RXDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXDIS_DEFAULT (_LEUART_CMD_RXDIS_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_TXEN (0x1UL << 2) /**< Transmitter Enable */
-#define _LEUART_CMD_TXEN_SHIFT 2 /**< Shift value for LEUART_TXEN */
-#define _LEUART_CMD_TXEN_MASK 0x4UL /**< Bit mask for LEUART_TXEN */
-#define _LEUART_CMD_TXEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_TXEN_DEFAULT (_LEUART_CMD_TXEN_DEFAULT << 2) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_TXDIS (0x1UL << 3) /**< Transmitter Disable */
-#define _LEUART_CMD_TXDIS_SHIFT 3 /**< Shift value for LEUART_TXDIS */
-#define _LEUART_CMD_TXDIS_MASK 0x8UL /**< Bit mask for LEUART_TXDIS */
-#define _LEUART_CMD_TXDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_TXDIS_DEFAULT (_LEUART_CMD_TXDIS_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXBLOCKEN (0x1UL << 4) /**< Receiver Block Enable */
-#define _LEUART_CMD_RXBLOCKEN_SHIFT 4 /**< Shift value for LEUART_RXBLOCKEN */
-#define _LEUART_CMD_RXBLOCKEN_MASK 0x10UL /**< Bit mask for LEUART_RXBLOCKEN */
-#define _LEUART_CMD_RXBLOCKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXBLOCKEN_DEFAULT (_LEUART_CMD_RXBLOCKEN_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXBLOCKDIS (0x1UL << 5) /**< Receiver Block Disable */
-#define _LEUART_CMD_RXBLOCKDIS_SHIFT 5 /**< Shift value for LEUART_RXBLOCKDIS */
-#define _LEUART_CMD_RXBLOCKDIS_MASK 0x20UL /**< Bit mask for LEUART_RXBLOCKDIS */
-#define _LEUART_CMD_RXBLOCKDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_RXBLOCKDIS_DEFAULT (_LEUART_CMD_RXBLOCKDIS_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_CLEARTX (0x1UL << 6) /**< Clear TX */
-#define _LEUART_CMD_CLEARTX_SHIFT 6 /**< Shift value for LEUART_CLEARTX */
-#define _LEUART_CMD_CLEARTX_MASK 0x40UL /**< Bit mask for LEUART_CLEARTX */
-#define _LEUART_CMD_CLEARTX_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_CLEARTX_DEFAULT (_LEUART_CMD_CLEARTX_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_CLEARRX (0x1UL << 7) /**< Clear RX */
-#define _LEUART_CMD_CLEARRX_SHIFT 7 /**< Shift value for LEUART_CLEARRX */
-#define _LEUART_CMD_CLEARRX_MASK 0x80UL /**< Bit mask for LEUART_CLEARRX */
-#define _LEUART_CMD_CLEARRX_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CMD */
-#define LEUART_CMD_CLEARRX_DEFAULT (_LEUART_CMD_CLEARRX_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_CMD */
-
-/* Bit fields for LEUART STATUS */
-#define _LEUART_STATUS_RESETVALUE 0x00000010UL /**< Default value for LEUART_STATUS */
-#define _LEUART_STATUS_MASK 0x0000003FUL /**< Mask for LEUART_STATUS */
-#define LEUART_STATUS_RXENS (0x1UL << 0) /**< Receiver Enable Status */
-#define _LEUART_STATUS_RXENS_SHIFT 0 /**< Shift value for LEUART_RXENS */
-#define _LEUART_STATUS_RXENS_MASK 0x1UL /**< Bit mask for LEUART_RXENS */
-#define _LEUART_STATUS_RXENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_RXENS_DEFAULT (_LEUART_STATUS_RXENS_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_TXENS (0x1UL << 1) /**< Transmitter Enable Status */
-#define _LEUART_STATUS_TXENS_SHIFT 1 /**< Shift value for LEUART_TXENS */
-#define _LEUART_STATUS_TXENS_MASK 0x2UL /**< Bit mask for LEUART_TXENS */
-#define _LEUART_STATUS_TXENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_TXENS_DEFAULT (_LEUART_STATUS_TXENS_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_RXBLOCK (0x1UL << 2) /**< Block Incoming Data */
-#define _LEUART_STATUS_RXBLOCK_SHIFT 2 /**< Shift value for LEUART_RXBLOCK */
-#define _LEUART_STATUS_RXBLOCK_MASK 0x4UL /**< Bit mask for LEUART_RXBLOCK */
-#define _LEUART_STATUS_RXBLOCK_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_RXBLOCK_DEFAULT (_LEUART_STATUS_RXBLOCK_DEFAULT << 2) /**< Shifted mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_TXC (0x1UL << 3) /**< TX Complete */
-#define _LEUART_STATUS_TXC_SHIFT 3 /**< Shift value for LEUART_TXC */
-#define _LEUART_STATUS_TXC_MASK 0x8UL /**< Bit mask for LEUART_TXC */
-#define _LEUART_STATUS_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_TXC_DEFAULT (_LEUART_STATUS_TXC_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_TXBL (0x1UL << 4) /**< TX Buffer Level */
-#define _LEUART_STATUS_TXBL_SHIFT 4 /**< Shift value for LEUART_TXBL */
-#define _LEUART_STATUS_TXBL_MASK 0x10UL /**< Bit mask for LEUART_TXBL */
-#define _LEUART_STATUS_TXBL_DEFAULT 0x00000001UL /**< Mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_TXBL_DEFAULT (_LEUART_STATUS_TXBL_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_RXDATAV (0x1UL << 5) /**< RX Data Valid */
-#define _LEUART_STATUS_RXDATAV_SHIFT 5 /**< Shift value for LEUART_RXDATAV */
-#define _LEUART_STATUS_RXDATAV_MASK 0x20UL /**< Bit mask for LEUART_RXDATAV */
-#define _LEUART_STATUS_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_STATUS */
-#define LEUART_STATUS_RXDATAV_DEFAULT (_LEUART_STATUS_RXDATAV_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_STATUS */
-
-/* Bit fields for LEUART CLKDIV */
-#define _LEUART_CLKDIV_RESETVALUE 0x00000000UL /**< Default value for LEUART_CLKDIV */
-#define _LEUART_CLKDIV_MASK 0x00007FF8UL /**< Mask for LEUART_CLKDIV */
-#define _LEUART_CLKDIV_DIV_SHIFT 3 /**< Shift value for LEUART_DIV */
-#define _LEUART_CLKDIV_DIV_MASK 0x7FF8UL /**< Bit mask for LEUART_DIV */
-#define _LEUART_CLKDIV_DIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_CLKDIV */
-#define LEUART_CLKDIV_DIV_DEFAULT (_LEUART_CLKDIV_DIV_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_CLKDIV */
-
-/* Bit fields for LEUART STARTFRAME */
-#define _LEUART_STARTFRAME_RESETVALUE 0x00000000UL /**< Default value for LEUART_STARTFRAME */
-#define _LEUART_STARTFRAME_MASK 0x000001FFUL /**< Mask for LEUART_STARTFRAME */
-#define _LEUART_STARTFRAME_STARTFRAME_SHIFT 0 /**< Shift value for LEUART_STARTFRAME */
-#define _LEUART_STARTFRAME_STARTFRAME_MASK 0x1FFUL /**< Bit mask for LEUART_STARTFRAME */
-#define _LEUART_STARTFRAME_STARTFRAME_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_STARTFRAME */
-#define LEUART_STARTFRAME_STARTFRAME_DEFAULT (_LEUART_STARTFRAME_STARTFRAME_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_STARTFRAME */
-
-/* Bit fields for LEUART SIGFRAME */
-#define _LEUART_SIGFRAME_RESETVALUE 0x00000000UL /**< Default value for LEUART_SIGFRAME */
-#define _LEUART_SIGFRAME_MASK 0x000001FFUL /**< Mask for LEUART_SIGFRAME */
-#define _LEUART_SIGFRAME_SIGFRAME_SHIFT 0 /**< Shift value for LEUART_SIGFRAME */
-#define _LEUART_SIGFRAME_SIGFRAME_MASK 0x1FFUL /**< Bit mask for LEUART_SIGFRAME */
-#define _LEUART_SIGFRAME_SIGFRAME_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SIGFRAME */
-#define LEUART_SIGFRAME_SIGFRAME_DEFAULT (_LEUART_SIGFRAME_SIGFRAME_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_SIGFRAME */
-
-/* Bit fields for LEUART RXDATAX */
-#define _LEUART_RXDATAX_RESETVALUE 0x00000000UL /**< Default value for LEUART_RXDATAX */
-#define _LEUART_RXDATAX_MASK 0x0000C1FFUL /**< Mask for LEUART_RXDATAX */
-#define _LEUART_RXDATAX_RXDATA_SHIFT 0 /**< Shift value for LEUART_RXDATA */
-#define _LEUART_RXDATAX_RXDATA_MASK 0x1FFUL /**< Bit mask for LEUART_RXDATA */
-#define _LEUART_RXDATAX_RXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATAX */
-#define LEUART_RXDATAX_RXDATA_DEFAULT (_LEUART_RXDATAX_RXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_RXDATAX */
-#define LEUART_RXDATAX_PERR (0x1UL << 14) /**< Receive Data Parity Error */
-#define _LEUART_RXDATAX_PERR_SHIFT 14 /**< Shift value for LEUART_PERR */
-#define _LEUART_RXDATAX_PERR_MASK 0x4000UL /**< Bit mask for LEUART_PERR */
-#define _LEUART_RXDATAX_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATAX */
-#define LEUART_RXDATAX_PERR_DEFAULT (_LEUART_RXDATAX_PERR_DEFAULT << 14) /**< Shifted mode DEFAULT for LEUART_RXDATAX */
-#define LEUART_RXDATAX_FERR (0x1UL << 15) /**< Receive Data Framing Error */
-#define _LEUART_RXDATAX_FERR_SHIFT 15 /**< Shift value for LEUART_FERR */
-#define _LEUART_RXDATAX_FERR_MASK 0x8000UL /**< Bit mask for LEUART_FERR */
-#define _LEUART_RXDATAX_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATAX */
-#define LEUART_RXDATAX_FERR_DEFAULT (_LEUART_RXDATAX_FERR_DEFAULT << 15) /**< Shifted mode DEFAULT for LEUART_RXDATAX */
-
-/* Bit fields for LEUART RXDATA */
-#define _LEUART_RXDATA_RESETVALUE 0x00000000UL /**< Default value for LEUART_RXDATA */
-#define _LEUART_RXDATA_MASK 0x000000FFUL /**< Mask for LEUART_RXDATA */
-#define _LEUART_RXDATA_RXDATA_SHIFT 0 /**< Shift value for LEUART_RXDATA */
-#define _LEUART_RXDATA_RXDATA_MASK 0xFFUL /**< Bit mask for LEUART_RXDATA */
-#define _LEUART_RXDATA_RXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATA */
-#define LEUART_RXDATA_RXDATA_DEFAULT (_LEUART_RXDATA_RXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_RXDATA */
-
-/* Bit fields for LEUART RXDATAXP */
-#define _LEUART_RXDATAXP_RESETVALUE 0x00000000UL /**< Default value for LEUART_RXDATAXP */
-#define _LEUART_RXDATAXP_MASK 0x0000C1FFUL /**< Mask for LEUART_RXDATAXP */
-#define _LEUART_RXDATAXP_RXDATAP_SHIFT 0 /**< Shift value for LEUART_RXDATAP */
-#define _LEUART_RXDATAXP_RXDATAP_MASK 0x1FFUL /**< Bit mask for LEUART_RXDATAP */
-#define _LEUART_RXDATAXP_RXDATAP_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATAXP */
-#define LEUART_RXDATAXP_RXDATAP_DEFAULT (_LEUART_RXDATAXP_RXDATAP_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_RXDATAXP */
-#define LEUART_RXDATAXP_PERRP (0x1UL << 14) /**< Receive Data Parity Error Peek */
-#define _LEUART_RXDATAXP_PERRP_SHIFT 14 /**< Shift value for LEUART_PERRP */
-#define _LEUART_RXDATAXP_PERRP_MASK 0x4000UL /**< Bit mask for LEUART_PERRP */
-#define _LEUART_RXDATAXP_PERRP_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATAXP */
-#define LEUART_RXDATAXP_PERRP_DEFAULT (_LEUART_RXDATAXP_PERRP_DEFAULT << 14) /**< Shifted mode DEFAULT for LEUART_RXDATAXP */
-#define LEUART_RXDATAXP_FERRP (0x1UL << 15) /**< Receive Data Framing Error Peek */
-#define _LEUART_RXDATAXP_FERRP_SHIFT 15 /**< Shift value for LEUART_FERRP */
-#define _LEUART_RXDATAXP_FERRP_MASK 0x8000UL /**< Bit mask for LEUART_FERRP */
-#define _LEUART_RXDATAXP_FERRP_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_RXDATAXP */
-#define LEUART_RXDATAXP_FERRP_DEFAULT (_LEUART_RXDATAXP_FERRP_DEFAULT << 15) /**< Shifted mode DEFAULT for LEUART_RXDATAXP */
-
-/* Bit fields for LEUART TXDATAX */
-#define _LEUART_TXDATAX_RESETVALUE 0x00000000UL /**< Default value for LEUART_TXDATAX */
-#define _LEUART_TXDATAX_MASK 0x0000E1FFUL /**< Mask for LEUART_TXDATAX */
-#define _LEUART_TXDATAX_TXDATA_SHIFT 0 /**< Shift value for LEUART_TXDATA */
-#define _LEUART_TXDATAX_TXDATA_MASK 0x1FFUL /**< Bit mask for LEUART_TXDATA */
-#define _LEUART_TXDATAX_TXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_TXDATA_DEFAULT (_LEUART_TXDATAX_TXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_TXBREAK (0x1UL << 13) /**< Transmit Data As Break */
-#define _LEUART_TXDATAX_TXBREAK_SHIFT 13 /**< Shift value for LEUART_TXBREAK */
-#define _LEUART_TXDATAX_TXBREAK_MASK 0x2000UL /**< Bit mask for LEUART_TXBREAK */
-#define _LEUART_TXDATAX_TXBREAK_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_TXBREAK_DEFAULT (_LEUART_TXDATAX_TXBREAK_DEFAULT << 13) /**< Shifted mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_TXDISAT (0x1UL << 14) /**< Disable TX After Transmission */
-#define _LEUART_TXDATAX_TXDISAT_SHIFT 14 /**< Shift value for LEUART_TXDISAT */
-#define _LEUART_TXDATAX_TXDISAT_MASK 0x4000UL /**< Bit mask for LEUART_TXDISAT */
-#define _LEUART_TXDATAX_TXDISAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_TXDISAT_DEFAULT (_LEUART_TXDATAX_TXDISAT_DEFAULT << 14) /**< Shifted mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_RXENAT (0x1UL << 15) /**< Enable RX After Transmission */
-#define _LEUART_TXDATAX_RXENAT_SHIFT 15 /**< Shift value for LEUART_RXENAT */
-#define _LEUART_TXDATAX_RXENAT_MASK 0x8000UL /**< Bit mask for LEUART_RXENAT */
-#define _LEUART_TXDATAX_RXENAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_TXDATAX */
-#define LEUART_TXDATAX_RXENAT_DEFAULT (_LEUART_TXDATAX_RXENAT_DEFAULT << 15) /**< Shifted mode DEFAULT for LEUART_TXDATAX */
-
-/* Bit fields for LEUART TXDATA */
-#define _LEUART_TXDATA_RESETVALUE 0x00000000UL /**< Default value for LEUART_TXDATA */
-#define _LEUART_TXDATA_MASK 0x000000FFUL /**< Mask for LEUART_TXDATA */
-#define _LEUART_TXDATA_TXDATA_SHIFT 0 /**< Shift value for LEUART_TXDATA */
-#define _LEUART_TXDATA_TXDATA_MASK 0xFFUL /**< Bit mask for LEUART_TXDATA */
-#define _LEUART_TXDATA_TXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_TXDATA */
-#define LEUART_TXDATA_TXDATA_DEFAULT (_LEUART_TXDATA_TXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_TXDATA */
-
-/* Bit fields for LEUART IF */
-#define _LEUART_IF_RESETVALUE 0x00000002UL /**< Default value for LEUART_IF */
-#define _LEUART_IF_MASK 0x000007FFUL /**< Mask for LEUART_IF */
-#define LEUART_IF_TXC (0x1UL << 0) /**< TX Complete Interrupt Flag */
-#define _LEUART_IF_TXC_SHIFT 0 /**< Shift value for LEUART_TXC */
-#define _LEUART_IF_TXC_MASK 0x1UL /**< Bit mask for LEUART_TXC */
-#define _LEUART_IF_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_TXC_DEFAULT (_LEUART_IF_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_TXBL (0x1UL << 1) /**< TX Buffer Level Interrupt Flag */
-#define _LEUART_IF_TXBL_SHIFT 1 /**< Shift value for LEUART_TXBL */
-#define _LEUART_IF_TXBL_MASK 0x2UL /**< Bit mask for LEUART_TXBL */
-#define _LEUART_IF_TXBL_DEFAULT 0x00000001UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_TXBL_DEFAULT (_LEUART_IF_TXBL_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_RXDATAV (0x1UL << 2) /**< RX Data Valid Interrupt Flag */
-#define _LEUART_IF_RXDATAV_SHIFT 2 /**< Shift value for LEUART_RXDATAV */
-#define _LEUART_IF_RXDATAV_MASK 0x4UL /**< Bit mask for LEUART_RXDATAV */
-#define _LEUART_IF_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_RXDATAV_DEFAULT (_LEUART_IF_RXDATAV_DEFAULT << 2) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_RXOF (0x1UL << 3) /**< RX Overflow Interrupt Flag */
-#define _LEUART_IF_RXOF_SHIFT 3 /**< Shift value for LEUART_RXOF */
-#define _LEUART_IF_RXOF_MASK 0x8UL /**< Bit mask for LEUART_RXOF */
-#define _LEUART_IF_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_RXOF_DEFAULT (_LEUART_IF_RXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_RXUF (0x1UL << 4) /**< RX Underflow Interrupt Flag */
-#define _LEUART_IF_RXUF_SHIFT 4 /**< Shift value for LEUART_RXUF */
-#define _LEUART_IF_RXUF_MASK 0x10UL /**< Bit mask for LEUART_RXUF */
-#define _LEUART_IF_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_RXUF_DEFAULT (_LEUART_IF_RXUF_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_TXOF (0x1UL << 5) /**< TX Overflow Interrupt Flag */
-#define _LEUART_IF_TXOF_SHIFT 5 /**< Shift value for LEUART_TXOF */
-#define _LEUART_IF_TXOF_MASK 0x20UL /**< Bit mask for LEUART_TXOF */
-#define _LEUART_IF_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_TXOF_DEFAULT (_LEUART_IF_TXOF_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_PERR (0x1UL << 6) /**< Parity Error Interrupt Flag */
-#define _LEUART_IF_PERR_SHIFT 6 /**< Shift value for LEUART_PERR */
-#define _LEUART_IF_PERR_MASK 0x40UL /**< Bit mask for LEUART_PERR */
-#define _LEUART_IF_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_PERR_DEFAULT (_LEUART_IF_PERR_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_FERR (0x1UL << 7) /**< Framing Error Interrupt Flag */
-#define _LEUART_IF_FERR_SHIFT 7 /**< Shift value for LEUART_FERR */
-#define _LEUART_IF_FERR_MASK 0x80UL /**< Bit mask for LEUART_FERR */
-#define _LEUART_IF_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_FERR_DEFAULT (_LEUART_IF_FERR_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_MPAF (0x1UL << 8) /**< Multi-Processor Address Frame Interrupt Flag */
-#define _LEUART_IF_MPAF_SHIFT 8 /**< Shift value for LEUART_MPAF */
-#define _LEUART_IF_MPAF_MASK 0x100UL /**< Bit mask for LEUART_MPAF */
-#define _LEUART_IF_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_MPAF_DEFAULT (_LEUART_IF_MPAF_DEFAULT << 8) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_STARTF (0x1UL << 9) /**< Start Frame Interrupt Flag */
-#define _LEUART_IF_STARTF_SHIFT 9 /**< Shift value for LEUART_STARTF */
-#define _LEUART_IF_STARTF_MASK 0x200UL /**< Bit mask for LEUART_STARTF */
-#define _LEUART_IF_STARTF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_STARTF_DEFAULT (_LEUART_IF_STARTF_DEFAULT << 9) /**< Shifted mode DEFAULT for LEUART_IF */
-#define LEUART_IF_SIGF (0x1UL << 10) /**< Signal Frame Interrupt Flag */
-#define _LEUART_IF_SIGF_SHIFT 10 /**< Shift value for LEUART_SIGF */
-#define _LEUART_IF_SIGF_MASK 0x400UL /**< Bit mask for LEUART_SIGF */
-#define _LEUART_IF_SIGF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IF */
-#define LEUART_IF_SIGF_DEFAULT (_LEUART_IF_SIGF_DEFAULT << 10) /**< Shifted mode DEFAULT for LEUART_IF */
-
-/* Bit fields for LEUART IFS */
-#define _LEUART_IFS_RESETVALUE 0x00000000UL /**< Default value for LEUART_IFS */
-#define _LEUART_IFS_MASK 0x000007F9UL /**< Mask for LEUART_IFS */
-#define LEUART_IFS_TXC (0x1UL << 0) /**< Set TX Complete Interrupt Flag */
-#define _LEUART_IFS_TXC_SHIFT 0 /**< Shift value for LEUART_TXC */
-#define _LEUART_IFS_TXC_MASK 0x1UL /**< Bit mask for LEUART_TXC */
-#define _LEUART_IFS_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_TXC_DEFAULT (_LEUART_IFS_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_RXOF (0x1UL << 3) /**< Set RX Overflow Interrupt Flag */
-#define _LEUART_IFS_RXOF_SHIFT 3 /**< Shift value for LEUART_RXOF */
-#define _LEUART_IFS_RXOF_MASK 0x8UL /**< Bit mask for LEUART_RXOF */
-#define _LEUART_IFS_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_RXOF_DEFAULT (_LEUART_IFS_RXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_RXUF (0x1UL << 4) /**< Set RX Underflow Interrupt Flag */
-#define _LEUART_IFS_RXUF_SHIFT 4 /**< Shift value for LEUART_RXUF */
-#define _LEUART_IFS_RXUF_MASK 0x10UL /**< Bit mask for LEUART_RXUF */
-#define _LEUART_IFS_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_RXUF_DEFAULT (_LEUART_IFS_RXUF_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_TXOF (0x1UL << 5) /**< Set TX Overflow Interrupt Flag */
-#define _LEUART_IFS_TXOF_SHIFT 5 /**< Shift value for LEUART_TXOF */
-#define _LEUART_IFS_TXOF_MASK 0x20UL /**< Bit mask for LEUART_TXOF */
-#define _LEUART_IFS_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_TXOF_DEFAULT (_LEUART_IFS_TXOF_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_PERR (0x1UL << 6) /**< Set Parity Error Interrupt Flag */
-#define _LEUART_IFS_PERR_SHIFT 6 /**< Shift value for LEUART_PERR */
-#define _LEUART_IFS_PERR_MASK 0x40UL /**< Bit mask for LEUART_PERR */
-#define _LEUART_IFS_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_PERR_DEFAULT (_LEUART_IFS_PERR_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_FERR (0x1UL << 7) /**< Set Framing Error Interrupt Flag */
-#define _LEUART_IFS_FERR_SHIFT 7 /**< Shift value for LEUART_FERR */
-#define _LEUART_IFS_FERR_MASK 0x80UL /**< Bit mask for LEUART_FERR */
-#define _LEUART_IFS_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_FERR_DEFAULT (_LEUART_IFS_FERR_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_MPAF (0x1UL << 8) /**< Set Multi-Processor Address Frame Interrupt Flag */
-#define _LEUART_IFS_MPAF_SHIFT 8 /**< Shift value for LEUART_MPAF */
-#define _LEUART_IFS_MPAF_MASK 0x100UL /**< Bit mask for LEUART_MPAF */
-#define _LEUART_IFS_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_MPAF_DEFAULT (_LEUART_IFS_MPAF_DEFAULT << 8) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_STARTF (0x1UL << 9) /**< Set Start Frame Interrupt Flag */
-#define _LEUART_IFS_STARTF_SHIFT 9 /**< Shift value for LEUART_STARTF */
-#define _LEUART_IFS_STARTF_MASK 0x200UL /**< Bit mask for LEUART_STARTF */
-#define _LEUART_IFS_STARTF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_STARTF_DEFAULT (_LEUART_IFS_STARTF_DEFAULT << 9) /**< Shifted mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_SIGF (0x1UL << 10) /**< Set Signal Frame Interrupt Flag */
-#define _LEUART_IFS_SIGF_SHIFT 10 /**< Shift value for LEUART_SIGF */
-#define _LEUART_IFS_SIGF_MASK 0x400UL /**< Bit mask for LEUART_SIGF */
-#define _LEUART_IFS_SIGF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFS */
-#define LEUART_IFS_SIGF_DEFAULT (_LEUART_IFS_SIGF_DEFAULT << 10) /**< Shifted mode DEFAULT for LEUART_IFS */
-
-/* Bit fields for LEUART IFC */
-#define _LEUART_IFC_RESETVALUE 0x00000000UL /**< Default value for LEUART_IFC */
-#define _LEUART_IFC_MASK 0x000007F9UL /**< Mask for LEUART_IFC */
-#define LEUART_IFC_TXC (0x1UL << 0) /**< Clear TX Complete Interrupt Flag */
-#define _LEUART_IFC_TXC_SHIFT 0 /**< Shift value for LEUART_TXC */
-#define _LEUART_IFC_TXC_MASK 0x1UL /**< Bit mask for LEUART_TXC */
-#define _LEUART_IFC_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_TXC_DEFAULT (_LEUART_IFC_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_RXOF (0x1UL << 3) /**< Clear RX Overflow Interrupt Flag */
-#define _LEUART_IFC_RXOF_SHIFT 3 /**< Shift value for LEUART_RXOF */
-#define _LEUART_IFC_RXOF_MASK 0x8UL /**< Bit mask for LEUART_RXOF */
-#define _LEUART_IFC_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_RXOF_DEFAULT (_LEUART_IFC_RXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_RXUF (0x1UL << 4) /**< Clear RX Underflow Interrupt Flag */
-#define _LEUART_IFC_RXUF_SHIFT 4 /**< Shift value for LEUART_RXUF */
-#define _LEUART_IFC_RXUF_MASK 0x10UL /**< Bit mask for LEUART_RXUF */
-#define _LEUART_IFC_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_RXUF_DEFAULT (_LEUART_IFC_RXUF_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_TXOF (0x1UL << 5) /**< Clear TX Overflow Interrupt Flag */
-#define _LEUART_IFC_TXOF_SHIFT 5 /**< Shift value for LEUART_TXOF */
-#define _LEUART_IFC_TXOF_MASK 0x20UL /**< Bit mask for LEUART_TXOF */
-#define _LEUART_IFC_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_TXOF_DEFAULT (_LEUART_IFC_TXOF_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_PERR (0x1UL << 6) /**< Clear Parity Error Interrupt Flag */
-#define _LEUART_IFC_PERR_SHIFT 6 /**< Shift value for LEUART_PERR */
-#define _LEUART_IFC_PERR_MASK 0x40UL /**< Bit mask for LEUART_PERR */
-#define _LEUART_IFC_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_PERR_DEFAULT (_LEUART_IFC_PERR_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_FERR (0x1UL << 7) /**< Clear Framing Error Interrupt Flag */
-#define _LEUART_IFC_FERR_SHIFT 7 /**< Shift value for LEUART_FERR */
-#define _LEUART_IFC_FERR_MASK 0x80UL /**< Bit mask for LEUART_FERR */
-#define _LEUART_IFC_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_FERR_DEFAULT (_LEUART_IFC_FERR_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_MPAF (0x1UL << 8) /**< Clear Multi-Processor Address Frame Interrupt Flag */
-#define _LEUART_IFC_MPAF_SHIFT 8 /**< Shift value for LEUART_MPAF */
-#define _LEUART_IFC_MPAF_MASK 0x100UL /**< Bit mask for LEUART_MPAF */
-#define _LEUART_IFC_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_MPAF_DEFAULT (_LEUART_IFC_MPAF_DEFAULT << 8) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_STARTF (0x1UL << 9) /**< Clear Start-Frame Interrupt Flag */
-#define _LEUART_IFC_STARTF_SHIFT 9 /**< Shift value for LEUART_STARTF */
-#define _LEUART_IFC_STARTF_MASK 0x200UL /**< Bit mask for LEUART_STARTF */
-#define _LEUART_IFC_STARTF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_STARTF_DEFAULT (_LEUART_IFC_STARTF_DEFAULT << 9) /**< Shifted mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_SIGF (0x1UL << 10) /**< Clear Signal-Frame Interrupt Flag */
-#define _LEUART_IFC_SIGF_SHIFT 10 /**< Shift value for LEUART_SIGF */
-#define _LEUART_IFC_SIGF_MASK 0x400UL /**< Bit mask for LEUART_SIGF */
-#define _LEUART_IFC_SIGF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IFC */
-#define LEUART_IFC_SIGF_DEFAULT (_LEUART_IFC_SIGF_DEFAULT << 10) /**< Shifted mode DEFAULT for LEUART_IFC */
-
-/* Bit fields for LEUART IEN */
-#define _LEUART_IEN_RESETVALUE 0x00000000UL /**< Default value for LEUART_IEN */
-#define _LEUART_IEN_MASK 0x000007FFUL /**< Mask for LEUART_IEN */
-#define LEUART_IEN_TXC (0x1UL << 0) /**< TX Complete Interrupt Enable */
-#define _LEUART_IEN_TXC_SHIFT 0 /**< Shift value for LEUART_TXC */
-#define _LEUART_IEN_TXC_MASK 0x1UL /**< Bit mask for LEUART_TXC */
-#define _LEUART_IEN_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_TXC_DEFAULT (_LEUART_IEN_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_TXBL (0x1UL << 1) /**< TX Buffer Level Interrupt Enable */
-#define _LEUART_IEN_TXBL_SHIFT 1 /**< Shift value for LEUART_TXBL */
-#define _LEUART_IEN_TXBL_MASK 0x2UL /**< Bit mask for LEUART_TXBL */
-#define _LEUART_IEN_TXBL_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_TXBL_DEFAULT (_LEUART_IEN_TXBL_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_RXDATAV (0x1UL << 2) /**< RX Data Valid Interrupt Enable */
-#define _LEUART_IEN_RXDATAV_SHIFT 2 /**< Shift value for LEUART_RXDATAV */
-#define _LEUART_IEN_RXDATAV_MASK 0x4UL /**< Bit mask for LEUART_RXDATAV */
-#define _LEUART_IEN_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_RXDATAV_DEFAULT (_LEUART_IEN_RXDATAV_DEFAULT << 2) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_RXOF (0x1UL << 3) /**< RX Overflow Interrupt Enable */
-#define _LEUART_IEN_RXOF_SHIFT 3 /**< Shift value for LEUART_RXOF */
-#define _LEUART_IEN_RXOF_MASK 0x8UL /**< Bit mask for LEUART_RXOF */
-#define _LEUART_IEN_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_RXOF_DEFAULT (_LEUART_IEN_RXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_RXUF (0x1UL << 4) /**< RX Underflow Interrupt Enable */
-#define _LEUART_IEN_RXUF_SHIFT 4 /**< Shift value for LEUART_RXUF */
-#define _LEUART_IEN_RXUF_MASK 0x10UL /**< Bit mask for LEUART_RXUF */
-#define _LEUART_IEN_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_RXUF_DEFAULT (_LEUART_IEN_RXUF_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_TXOF (0x1UL << 5) /**< TX Overflow Interrupt Enable */
-#define _LEUART_IEN_TXOF_SHIFT 5 /**< Shift value for LEUART_TXOF */
-#define _LEUART_IEN_TXOF_MASK 0x20UL /**< Bit mask for LEUART_TXOF */
-#define _LEUART_IEN_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_TXOF_DEFAULT (_LEUART_IEN_TXOF_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_PERR (0x1UL << 6) /**< Parity Error Interrupt Enable */
-#define _LEUART_IEN_PERR_SHIFT 6 /**< Shift value for LEUART_PERR */
-#define _LEUART_IEN_PERR_MASK 0x40UL /**< Bit mask for LEUART_PERR */
-#define _LEUART_IEN_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_PERR_DEFAULT (_LEUART_IEN_PERR_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_FERR (0x1UL << 7) /**< Framing Error Interrupt Enable */
-#define _LEUART_IEN_FERR_SHIFT 7 /**< Shift value for LEUART_FERR */
-#define _LEUART_IEN_FERR_MASK 0x80UL /**< Bit mask for LEUART_FERR */
-#define _LEUART_IEN_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_FERR_DEFAULT (_LEUART_IEN_FERR_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_MPAF (0x1UL << 8) /**< Multi-Processor Address Frame Interrupt Enable */
-#define _LEUART_IEN_MPAF_SHIFT 8 /**< Shift value for LEUART_MPAF */
-#define _LEUART_IEN_MPAF_MASK 0x100UL /**< Bit mask for LEUART_MPAF */
-#define _LEUART_IEN_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_MPAF_DEFAULT (_LEUART_IEN_MPAF_DEFAULT << 8) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_STARTF (0x1UL << 9) /**< Start Frame Interrupt Enable */
-#define _LEUART_IEN_STARTF_SHIFT 9 /**< Shift value for LEUART_STARTF */
-#define _LEUART_IEN_STARTF_MASK 0x200UL /**< Bit mask for LEUART_STARTF */
-#define _LEUART_IEN_STARTF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_STARTF_DEFAULT (_LEUART_IEN_STARTF_DEFAULT << 9) /**< Shifted mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_SIGF (0x1UL << 10) /**< Signal Frame Interrupt Enable */
-#define _LEUART_IEN_SIGF_SHIFT 10 /**< Shift value for LEUART_SIGF */
-#define _LEUART_IEN_SIGF_MASK 0x400UL /**< Bit mask for LEUART_SIGF */
-#define _LEUART_IEN_SIGF_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_IEN */
-#define LEUART_IEN_SIGF_DEFAULT (_LEUART_IEN_SIGF_DEFAULT << 10) /**< Shifted mode DEFAULT for LEUART_IEN */
-
-/* Bit fields for LEUART PULSECTRL */
-#define _LEUART_PULSECTRL_RESETVALUE 0x00000000UL /**< Default value for LEUART_PULSECTRL */
-#define _LEUART_PULSECTRL_MASK 0x0000003FUL /**< Mask for LEUART_PULSECTRL */
-#define _LEUART_PULSECTRL_PULSEW_SHIFT 0 /**< Shift value for LEUART_PULSEW */
-#define _LEUART_PULSECTRL_PULSEW_MASK 0xFUL /**< Bit mask for LEUART_PULSEW */
-#define _LEUART_PULSECTRL_PULSEW_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_PULSECTRL */
-#define LEUART_PULSECTRL_PULSEW_DEFAULT (_LEUART_PULSECTRL_PULSEW_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_PULSECTRL */
-#define LEUART_PULSECTRL_PULSEEN (0x1UL << 4) /**< Pulse Generator/Extender Enable */
-#define _LEUART_PULSECTRL_PULSEEN_SHIFT 4 /**< Shift value for LEUART_PULSEEN */
-#define _LEUART_PULSECTRL_PULSEEN_MASK 0x10UL /**< Bit mask for LEUART_PULSEEN */
-#define _LEUART_PULSECTRL_PULSEEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_PULSECTRL */
-#define LEUART_PULSECTRL_PULSEEN_DEFAULT (_LEUART_PULSECTRL_PULSEEN_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_PULSECTRL */
-#define LEUART_PULSECTRL_PULSEFILT (0x1UL << 5) /**< Pulse Filter */
-#define _LEUART_PULSECTRL_PULSEFILT_SHIFT 5 /**< Shift value for LEUART_PULSEFILT */
-#define _LEUART_PULSECTRL_PULSEFILT_MASK 0x20UL /**< Bit mask for LEUART_PULSEFILT */
-#define _LEUART_PULSECTRL_PULSEFILT_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_PULSECTRL */
-#define LEUART_PULSECTRL_PULSEFILT_DEFAULT (_LEUART_PULSECTRL_PULSEFILT_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_PULSECTRL */
-
-/* Bit fields for LEUART FREEZE */
-#define _LEUART_FREEZE_RESETVALUE 0x00000000UL /**< Default value for LEUART_FREEZE */
-#define _LEUART_FREEZE_MASK 0x00000001UL /**< Mask for LEUART_FREEZE */
-#define LEUART_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _LEUART_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for LEUART_REGFREEZE */
-#define _LEUART_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for LEUART_REGFREEZE */
-#define _LEUART_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_FREEZE */
-#define _LEUART_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for LEUART_FREEZE */
-#define _LEUART_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for LEUART_FREEZE */
-#define LEUART_FREEZE_REGFREEZE_DEFAULT (_LEUART_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_FREEZE */
-#define LEUART_FREEZE_REGFREEZE_UPDATE (_LEUART_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for LEUART_FREEZE */
-#define LEUART_FREEZE_REGFREEZE_FREEZE (_LEUART_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for LEUART_FREEZE */
-
-/* Bit fields for LEUART SYNCBUSY */
-#define _LEUART_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for LEUART_SYNCBUSY */
-#define _LEUART_SYNCBUSY_MASK 0x000000FFUL /**< Mask for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_CTRL (0x1UL << 0) /**< CTRL Register Busy */
-#define _LEUART_SYNCBUSY_CTRL_SHIFT 0 /**< Shift value for LEUART_CTRL */
-#define _LEUART_SYNCBUSY_CTRL_MASK 0x1UL /**< Bit mask for LEUART_CTRL */
-#define _LEUART_SYNCBUSY_CTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_CTRL_DEFAULT (_LEUART_SYNCBUSY_CTRL_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_CMD (0x1UL << 1) /**< CMD Register Busy */
-#define _LEUART_SYNCBUSY_CMD_SHIFT 1 /**< Shift value for LEUART_CMD */
-#define _LEUART_SYNCBUSY_CMD_MASK 0x2UL /**< Bit mask for LEUART_CMD */
-#define _LEUART_SYNCBUSY_CMD_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_CMD_DEFAULT (_LEUART_SYNCBUSY_CMD_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_CLKDIV (0x1UL << 2) /**< CLKDIV Register Busy */
-#define _LEUART_SYNCBUSY_CLKDIV_SHIFT 2 /**< Shift value for LEUART_CLKDIV */
-#define _LEUART_SYNCBUSY_CLKDIV_MASK 0x4UL /**< Bit mask for LEUART_CLKDIV */
-#define _LEUART_SYNCBUSY_CLKDIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_CLKDIV_DEFAULT (_LEUART_SYNCBUSY_CLKDIV_DEFAULT << 2) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_STARTFRAME (0x1UL << 3) /**< STARTFRAME Register Busy */
-#define _LEUART_SYNCBUSY_STARTFRAME_SHIFT 3 /**< Shift value for LEUART_STARTFRAME */
-#define _LEUART_SYNCBUSY_STARTFRAME_MASK 0x8UL /**< Bit mask for LEUART_STARTFRAME */
-#define _LEUART_SYNCBUSY_STARTFRAME_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_STARTFRAME_DEFAULT (_LEUART_SYNCBUSY_STARTFRAME_DEFAULT << 3) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_SIGFRAME (0x1UL << 4) /**< SIGFRAME Register Busy */
-#define _LEUART_SYNCBUSY_SIGFRAME_SHIFT 4 /**< Shift value for LEUART_SIGFRAME */
-#define _LEUART_SYNCBUSY_SIGFRAME_MASK 0x10UL /**< Bit mask for LEUART_SIGFRAME */
-#define _LEUART_SYNCBUSY_SIGFRAME_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_SIGFRAME_DEFAULT (_LEUART_SYNCBUSY_SIGFRAME_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_TXDATAX (0x1UL << 5) /**< TXDATAX Register Busy */
-#define _LEUART_SYNCBUSY_TXDATAX_SHIFT 5 /**< Shift value for LEUART_TXDATAX */
-#define _LEUART_SYNCBUSY_TXDATAX_MASK 0x20UL /**< Bit mask for LEUART_TXDATAX */
-#define _LEUART_SYNCBUSY_TXDATAX_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_TXDATAX_DEFAULT (_LEUART_SYNCBUSY_TXDATAX_DEFAULT << 5) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_TXDATA (0x1UL << 6) /**< TXDATA Register Busy */
-#define _LEUART_SYNCBUSY_TXDATA_SHIFT 6 /**< Shift value for LEUART_TXDATA */
-#define _LEUART_SYNCBUSY_TXDATA_MASK 0x40UL /**< Bit mask for LEUART_TXDATA */
-#define _LEUART_SYNCBUSY_TXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_TXDATA_DEFAULT (_LEUART_SYNCBUSY_TXDATA_DEFAULT << 6) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_PULSECTRL (0x1UL << 7) /**< PULSECTRL Register Busy */
-#define _LEUART_SYNCBUSY_PULSECTRL_SHIFT 7 /**< Shift value for LEUART_PULSECTRL */
-#define _LEUART_SYNCBUSY_PULSECTRL_MASK 0x80UL /**< Bit mask for LEUART_PULSECTRL */
-#define _LEUART_SYNCBUSY_PULSECTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_SYNCBUSY */
-#define LEUART_SYNCBUSY_PULSECTRL_DEFAULT (_LEUART_SYNCBUSY_PULSECTRL_DEFAULT << 7) /**< Shifted mode DEFAULT for LEUART_SYNCBUSY */
-
-/* Bit fields for LEUART ROUTE */
-#define _LEUART_ROUTE_RESETVALUE 0x00000000UL /**< Default value for LEUART_ROUTE */
-#define _LEUART_ROUTE_MASK 0x00000703UL /**< Mask for LEUART_ROUTE */
-#define LEUART_ROUTE_RXPEN (0x1UL << 0) /**< RX Pin Enable */
-#define _LEUART_ROUTE_RXPEN_SHIFT 0 /**< Shift value for LEUART_RXPEN */
-#define _LEUART_ROUTE_RXPEN_MASK 0x1UL /**< Bit mask for LEUART_RXPEN */
-#define _LEUART_ROUTE_RXPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_ROUTE */
-#define LEUART_ROUTE_RXPEN_DEFAULT (_LEUART_ROUTE_RXPEN_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_ROUTE */
-#define LEUART_ROUTE_TXPEN (0x1UL << 1) /**< TX Pin Enable */
-#define _LEUART_ROUTE_TXPEN_SHIFT 1 /**< Shift value for LEUART_TXPEN */
-#define _LEUART_ROUTE_TXPEN_MASK 0x2UL /**< Bit mask for LEUART_TXPEN */
-#define _LEUART_ROUTE_TXPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_ROUTE */
-#define LEUART_ROUTE_TXPEN_DEFAULT (_LEUART_ROUTE_TXPEN_DEFAULT << 1) /**< Shifted mode DEFAULT for LEUART_ROUTE */
-#define _LEUART_ROUTE_LOCATION_SHIFT 8 /**< Shift value for LEUART_LOCATION */
-#define _LEUART_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for LEUART_LOCATION */
-#define _LEUART_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for LEUART_ROUTE */
-#define _LEUART_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_ROUTE */
-#define _LEUART_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for LEUART_ROUTE */
-#define _LEUART_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for LEUART_ROUTE */
-#define _LEUART_ROUTE_LOCATION_LOC3 0x00000003UL /**< Mode LOC3 for LEUART_ROUTE */
-#define _LEUART_ROUTE_LOCATION_LOC4 0x00000004UL /**< Mode LOC4 for LEUART_ROUTE */
-#define LEUART_ROUTE_LOCATION_LOC0 (_LEUART_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for LEUART_ROUTE */
-#define LEUART_ROUTE_LOCATION_DEFAULT (_LEUART_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for LEUART_ROUTE */
-#define LEUART_ROUTE_LOCATION_LOC1 (_LEUART_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for LEUART_ROUTE */
-#define LEUART_ROUTE_LOCATION_LOC2 (_LEUART_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for LEUART_ROUTE */
-#define LEUART_ROUTE_LOCATION_LOC3 (_LEUART_ROUTE_LOCATION_LOC3 << 8) /**< Shifted mode LOC3 for LEUART_ROUTE */
-#define LEUART_ROUTE_LOCATION_LOC4 (_LEUART_ROUTE_LOCATION_LOC4 << 8) /**< Shifted mode LOC4 for LEUART_ROUTE */
-
-/* Bit fields for LEUART INPUT */
-#define _LEUART_INPUT_RESETVALUE 0x00000000UL /**< Default value for LEUART_INPUT */
-#define _LEUART_INPUT_MASK 0x00000013UL /**< Mask for LEUART_INPUT */
-#define _LEUART_INPUT_RXPRSSEL_SHIFT 0 /**< Shift value for LEUART_RXPRSSEL */
-#define _LEUART_INPUT_RXPRSSEL_MASK 0x3UL /**< Bit mask for LEUART_RXPRSSEL */
-#define _LEUART_INPUT_RXPRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_INPUT */
-#define _LEUART_INPUT_RXPRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for LEUART_INPUT */
-#define _LEUART_INPUT_RXPRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for LEUART_INPUT */
-#define _LEUART_INPUT_RXPRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for LEUART_INPUT */
-#define _LEUART_INPUT_RXPRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for LEUART_INPUT */
-#define LEUART_INPUT_RXPRSSEL_DEFAULT (_LEUART_INPUT_RXPRSSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for LEUART_INPUT */
-#define LEUART_INPUT_RXPRSSEL_PRSCH0 (_LEUART_INPUT_RXPRSSEL_PRSCH0 << 0) /**< Shifted mode PRSCH0 for LEUART_INPUT */
-#define LEUART_INPUT_RXPRSSEL_PRSCH1 (_LEUART_INPUT_RXPRSSEL_PRSCH1 << 0) /**< Shifted mode PRSCH1 for LEUART_INPUT */
-#define LEUART_INPUT_RXPRSSEL_PRSCH2 (_LEUART_INPUT_RXPRSSEL_PRSCH2 << 0) /**< Shifted mode PRSCH2 for LEUART_INPUT */
-#define LEUART_INPUT_RXPRSSEL_PRSCH3 (_LEUART_INPUT_RXPRSSEL_PRSCH3 << 0) /**< Shifted mode PRSCH3 for LEUART_INPUT */
-#define LEUART_INPUT_RXPRS (0x1UL << 4) /**< PRS RX Enable */
-#define _LEUART_INPUT_RXPRS_SHIFT 4 /**< Shift value for LEUART_RXPRS */
-#define _LEUART_INPUT_RXPRS_MASK 0x10UL /**< Bit mask for LEUART_RXPRS */
-#define _LEUART_INPUT_RXPRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for LEUART_INPUT */
-#define LEUART_INPUT_RXPRS_DEFAULT (_LEUART_INPUT_RXPRS_DEFAULT << 4) /**< Shifted mode DEFAULT for LEUART_INPUT */
-
-/** @} End of group EFM32ZG_LEUART */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_msc.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_msc.h
deleted file mode 100644
index 11ed6f8b91..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_msc.h
+++ /dev/null
@@ -1,419 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_MSC register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_MSC
- * @{
- * @brief EFM32ZG_MSC Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Memory System Control Register */
- __IOM uint32_t READCTRL; /**< Read Control Register */
- __IOM uint32_t WRITECTRL; /**< Write Control Register */
- __IOM uint32_t WRITECMD; /**< Write Command Register */
- __IOM uint32_t ADDRB; /**< Page Erase/Write Address Buffer */
-
- uint32_t RESERVED0[1U]; /**< Reserved for future use **/
- __IOM uint32_t WDATA; /**< Write Data Register */
- __IM uint32_t STATUS; /**< Status Register */
-
- uint32_t RESERVED1[3U]; /**< Reserved for future use **/
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t LOCK; /**< Configuration Lock Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t CACHEHITS; /**< Cache Hits Performance Counter */
- __IM uint32_t CACHEMISSES; /**< Cache Misses Performance Counter */
- uint32_t RESERVED2[1U]; /**< Reserved for future use **/
- __IOM uint32_t TIMEBASE; /**< Flash Write and Erase Timebase */
- __IOM uint32_t MASSLOCK; /**< Mass Erase Lock Register */
- __IOM uint32_t IRQLATENCY; /**< Irq Latency Register */
-} MSC_TypeDef; /** MSC Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_MSC_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for MSC CTRL */
-#define _MSC_CTRL_RESETVALUE 0x00000001UL /**< Default value for MSC_CTRL */
-#define _MSC_CTRL_MASK 0x00000001UL /**< Mask for MSC_CTRL */
-#define MSC_CTRL_BUSFAULT (0x1UL << 0) /**< Bus Fault Response Enable */
-#define _MSC_CTRL_BUSFAULT_SHIFT 0 /**< Shift value for MSC_BUSFAULT */
-#define _MSC_CTRL_BUSFAULT_MASK 0x1UL /**< Bit mask for MSC_BUSFAULT */
-#define _MSC_CTRL_BUSFAULT_GENERATE 0x00000000UL /**< Mode GENERATE for MSC_CTRL */
-#define _MSC_CTRL_BUSFAULT_DEFAULT 0x00000001UL /**< Mode DEFAULT for MSC_CTRL */
-#define _MSC_CTRL_BUSFAULT_IGNORE 0x00000001UL /**< Mode IGNORE for MSC_CTRL */
-#define MSC_CTRL_BUSFAULT_GENERATE (_MSC_CTRL_BUSFAULT_GENERATE << 0) /**< Shifted mode GENERATE for MSC_CTRL */
-#define MSC_CTRL_BUSFAULT_DEFAULT (_MSC_CTRL_BUSFAULT_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_CTRL */
-#define MSC_CTRL_BUSFAULT_IGNORE (_MSC_CTRL_BUSFAULT_IGNORE << 0) /**< Shifted mode IGNORE for MSC_CTRL */
-
-/* Bit fields for MSC READCTRL */
-#define _MSC_READCTRL_RESETVALUE 0x00000001UL /**< Default value for MSC_READCTRL */
-#define _MSC_READCTRL_MASK 0x0000009FUL /**< Mask for MSC_READCTRL */
-#define _MSC_READCTRL_MODE_SHIFT 0 /**< Shift value for MSC_MODE */
-#define _MSC_READCTRL_MODE_MASK 0x7UL /**< Bit mask for MSC_MODE */
-#define _MSC_READCTRL_MODE_WS0 0x00000000UL /**< Mode WS0 for MSC_READCTRL */
-#define _MSC_READCTRL_MODE_DEFAULT 0x00000001UL /**< Mode DEFAULT for MSC_READCTRL */
-#define _MSC_READCTRL_MODE_WS1 0x00000001UL /**< Mode WS1 for MSC_READCTRL */
-#define MSC_READCTRL_MODE_WS0 (_MSC_READCTRL_MODE_WS0 << 0) /**< Shifted mode WS0 for MSC_READCTRL */
-#define MSC_READCTRL_MODE_DEFAULT (_MSC_READCTRL_MODE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_READCTRL */
-#define MSC_READCTRL_MODE_WS1 (_MSC_READCTRL_MODE_WS1 << 0) /**< Shifted mode WS1 for MSC_READCTRL */
-#define MSC_READCTRL_IFCDIS (0x1UL << 3) /**< Internal Flash Cache Disable */
-#define _MSC_READCTRL_IFCDIS_SHIFT 3 /**< Shift value for MSC_IFCDIS */
-#define _MSC_READCTRL_IFCDIS_MASK 0x8UL /**< Bit mask for MSC_IFCDIS */
-#define _MSC_READCTRL_IFCDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_READCTRL */
-#define MSC_READCTRL_IFCDIS_DEFAULT (_MSC_READCTRL_IFCDIS_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_READCTRL */
-#define MSC_READCTRL_AIDIS (0x1UL << 4) /**< Automatic Invalidate Disable */
-#define _MSC_READCTRL_AIDIS_SHIFT 4 /**< Shift value for MSC_AIDIS */
-#define _MSC_READCTRL_AIDIS_MASK 0x10UL /**< Bit mask for MSC_AIDIS */
-#define _MSC_READCTRL_AIDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_READCTRL */
-#define MSC_READCTRL_AIDIS_DEFAULT (_MSC_READCTRL_AIDIS_DEFAULT << 4) /**< Shifted mode DEFAULT for MSC_READCTRL */
-#define MSC_READCTRL_RAMCEN (0x1UL << 7) /**< RAM Cache Enable */
-#define _MSC_READCTRL_RAMCEN_SHIFT 7 /**< Shift value for MSC_RAMCEN */
-#define _MSC_READCTRL_RAMCEN_MASK 0x80UL /**< Bit mask for MSC_RAMCEN */
-#define _MSC_READCTRL_RAMCEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_READCTRL */
-#define MSC_READCTRL_RAMCEN_DEFAULT (_MSC_READCTRL_RAMCEN_DEFAULT << 7) /**< Shifted mode DEFAULT for MSC_READCTRL */
-
-/* Bit fields for MSC WRITECTRL */
-#define _MSC_WRITECTRL_RESETVALUE 0x00000000UL /**< Default value for MSC_WRITECTRL */
-#define _MSC_WRITECTRL_MASK 0x00000003UL /**< Mask for MSC_WRITECTRL */
-#define MSC_WRITECTRL_WREN (0x1UL << 0) /**< Enable Write/Erase Controller */
-#define _MSC_WRITECTRL_WREN_SHIFT 0 /**< Shift value for MSC_WREN */
-#define _MSC_WRITECTRL_WREN_MASK 0x1UL /**< Bit mask for MSC_WREN */
-#define _MSC_WRITECTRL_WREN_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECTRL */
-#define MSC_WRITECTRL_WREN_DEFAULT (_MSC_WRITECTRL_WREN_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_WRITECTRL */
-#define MSC_WRITECTRL_IRQERASEABORT (0x1UL << 1) /**< Abort Page Erase on Interrupt */
-#define _MSC_WRITECTRL_IRQERASEABORT_SHIFT 1 /**< Shift value for MSC_IRQERASEABORT */
-#define _MSC_WRITECTRL_IRQERASEABORT_MASK 0x2UL /**< Bit mask for MSC_IRQERASEABORT */
-#define _MSC_WRITECTRL_IRQERASEABORT_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECTRL */
-#define MSC_WRITECTRL_IRQERASEABORT_DEFAULT (_MSC_WRITECTRL_IRQERASEABORT_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_WRITECTRL */
-
-/* Bit fields for MSC WRITECMD */
-#define _MSC_WRITECMD_RESETVALUE 0x00000000UL /**< Default value for MSC_WRITECMD */
-#define _MSC_WRITECMD_MASK 0x0000113FUL /**< Mask for MSC_WRITECMD */
-#define MSC_WRITECMD_LADDRIM (0x1UL << 0) /**< Load MSC_ADDRB into ADDR */
-#define _MSC_WRITECMD_LADDRIM_SHIFT 0 /**< Shift value for MSC_LADDRIM */
-#define _MSC_WRITECMD_LADDRIM_MASK 0x1UL /**< Bit mask for MSC_LADDRIM */
-#define _MSC_WRITECMD_LADDRIM_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_LADDRIM_DEFAULT (_MSC_WRITECMD_LADDRIM_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_ERASEPAGE (0x1UL << 1) /**< Erase Page */
-#define _MSC_WRITECMD_ERASEPAGE_SHIFT 1 /**< Shift value for MSC_ERASEPAGE */
-#define _MSC_WRITECMD_ERASEPAGE_MASK 0x2UL /**< Bit mask for MSC_ERASEPAGE */
-#define _MSC_WRITECMD_ERASEPAGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_ERASEPAGE_DEFAULT (_MSC_WRITECMD_ERASEPAGE_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_WRITEEND (0x1UL << 2) /**< End Write Mode */
-#define _MSC_WRITECMD_WRITEEND_SHIFT 2 /**< Shift value for MSC_WRITEEND */
-#define _MSC_WRITECMD_WRITEEND_MASK 0x4UL /**< Bit mask for MSC_WRITEEND */
-#define _MSC_WRITECMD_WRITEEND_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_WRITEEND_DEFAULT (_MSC_WRITECMD_WRITEEND_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_WRITEONCE (0x1UL << 3) /**< Word Write-Once Trigger */
-#define _MSC_WRITECMD_WRITEONCE_SHIFT 3 /**< Shift value for MSC_WRITEONCE */
-#define _MSC_WRITECMD_WRITEONCE_MASK 0x8UL /**< Bit mask for MSC_WRITEONCE */
-#define _MSC_WRITECMD_WRITEONCE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_WRITEONCE_DEFAULT (_MSC_WRITECMD_WRITEONCE_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_WRITETRIG (0x1UL << 4) /**< Word Write Sequence Trigger */
-#define _MSC_WRITECMD_WRITETRIG_SHIFT 4 /**< Shift value for MSC_WRITETRIG */
-#define _MSC_WRITECMD_WRITETRIG_MASK 0x10UL /**< Bit mask for MSC_WRITETRIG */
-#define _MSC_WRITECMD_WRITETRIG_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_WRITETRIG_DEFAULT (_MSC_WRITECMD_WRITETRIG_DEFAULT << 4) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_ERASEABORT (0x1UL << 5) /**< Abort erase sequence */
-#define _MSC_WRITECMD_ERASEABORT_SHIFT 5 /**< Shift value for MSC_ERASEABORT */
-#define _MSC_WRITECMD_ERASEABORT_MASK 0x20UL /**< Bit mask for MSC_ERASEABORT */
-#define _MSC_WRITECMD_ERASEABORT_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_ERASEABORT_DEFAULT (_MSC_WRITECMD_ERASEABORT_DEFAULT << 5) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_ERASEMAIN0 (0x1UL << 8) /**< Mass erase region 0 */
-#define _MSC_WRITECMD_ERASEMAIN0_SHIFT 8 /**< Shift value for MSC_ERASEMAIN0 */
-#define _MSC_WRITECMD_ERASEMAIN0_MASK 0x100UL /**< Bit mask for MSC_ERASEMAIN0 */
-#define _MSC_WRITECMD_ERASEMAIN0_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_ERASEMAIN0_DEFAULT (_MSC_WRITECMD_ERASEMAIN0_DEFAULT << 8) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_CLEARWDATA (0x1UL << 12) /**< Clear WDATA state */
-#define _MSC_WRITECMD_CLEARWDATA_SHIFT 12 /**< Shift value for MSC_CLEARWDATA */
-#define _MSC_WRITECMD_CLEARWDATA_MASK 0x1000UL /**< Bit mask for MSC_CLEARWDATA */
-#define _MSC_WRITECMD_CLEARWDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WRITECMD */
-#define MSC_WRITECMD_CLEARWDATA_DEFAULT (_MSC_WRITECMD_CLEARWDATA_DEFAULT << 12) /**< Shifted mode DEFAULT for MSC_WRITECMD */
-
-/* Bit fields for MSC ADDRB */
-#define _MSC_ADDRB_RESETVALUE 0x00000000UL /**< Default value for MSC_ADDRB */
-#define _MSC_ADDRB_MASK 0xFFFFFFFFUL /**< Mask for MSC_ADDRB */
-#define _MSC_ADDRB_ADDRB_SHIFT 0 /**< Shift value for MSC_ADDRB */
-#define _MSC_ADDRB_ADDRB_MASK 0xFFFFFFFFUL /**< Bit mask for MSC_ADDRB */
-#define _MSC_ADDRB_ADDRB_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_ADDRB */
-#define MSC_ADDRB_ADDRB_DEFAULT (_MSC_ADDRB_ADDRB_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_ADDRB */
-
-/* Bit fields for MSC WDATA */
-#define _MSC_WDATA_RESETVALUE 0x00000000UL /**< Default value for MSC_WDATA */
-#define _MSC_WDATA_MASK 0xFFFFFFFFUL /**< Mask for MSC_WDATA */
-#define _MSC_WDATA_WDATA_SHIFT 0 /**< Shift value for MSC_WDATA */
-#define _MSC_WDATA_WDATA_MASK 0xFFFFFFFFUL /**< Bit mask for MSC_WDATA */
-#define _MSC_WDATA_WDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_WDATA */
-#define MSC_WDATA_WDATA_DEFAULT (_MSC_WDATA_WDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_WDATA */
-
-/* Bit fields for MSC STATUS */
-#define _MSC_STATUS_RESETVALUE 0x00000008UL /**< Default value for MSC_STATUS */
-#define _MSC_STATUS_MASK 0x0000007FUL /**< Mask for MSC_STATUS */
-#define MSC_STATUS_BUSY (0x1UL << 0) /**< Erase/Write Busy */
-#define _MSC_STATUS_BUSY_SHIFT 0 /**< Shift value for MSC_BUSY */
-#define _MSC_STATUS_BUSY_MASK 0x1UL /**< Bit mask for MSC_BUSY */
-#define _MSC_STATUS_BUSY_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_BUSY_DEFAULT (_MSC_STATUS_BUSY_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_LOCKED (0x1UL << 1) /**< Access Locked */
-#define _MSC_STATUS_LOCKED_SHIFT 1 /**< Shift value for MSC_LOCKED */
-#define _MSC_STATUS_LOCKED_MASK 0x2UL /**< Bit mask for MSC_LOCKED */
-#define _MSC_STATUS_LOCKED_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_LOCKED_DEFAULT (_MSC_STATUS_LOCKED_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_INVADDR (0x1UL << 2) /**< Invalid Write Address or Erase Page */
-#define _MSC_STATUS_INVADDR_SHIFT 2 /**< Shift value for MSC_INVADDR */
-#define _MSC_STATUS_INVADDR_MASK 0x4UL /**< Bit mask for MSC_INVADDR */
-#define _MSC_STATUS_INVADDR_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_INVADDR_DEFAULT (_MSC_STATUS_INVADDR_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_WDATAREADY (0x1UL << 3) /**< WDATA Write Ready */
-#define _MSC_STATUS_WDATAREADY_SHIFT 3 /**< Shift value for MSC_WDATAREADY */
-#define _MSC_STATUS_WDATAREADY_MASK 0x8UL /**< Bit mask for MSC_WDATAREADY */
-#define _MSC_STATUS_WDATAREADY_DEFAULT 0x00000001UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_WDATAREADY_DEFAULT (_MSC_STATUS_WDATAREADY_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_WORDTIMEOUT (0x1UL << 4) /**< Flash Write Word Timeout */
-#define _MSC_STATUS_WORDTIMEOUT_SHIFT 4 /**< Shift value for MSC_WORDTIMEOUT */
-#define _MSC_STATUS_WORDTIMEOUT_MASK 0x10UL /**< Bit mask for MSC_WORDTIMEOUT */
-#define _MSC_STATUS_WORDTIMEOUT_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_WORDTIMEOUT_DEFAULT (_MSC_STATUS_WORDTIMEOUT_DEFAULT << 4) /**< Shifted mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_ERASEABORTED (0x1UL << 5) /**< The Current Flash Erase Operation Aborted */
-#define _MSC_STATUS_ERASEABORTED_SHIFT 5 /**< Shift value for MSC_ERASEABORTED */
-#define _MSC_STATUS_ERASEABORTED_MASK 0x20UL /**< Bit mask for MSC_ERASEABORTED */
-#define _MSC_STATUS_ERASEABORTED_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_ERASEABORTED_DEFAULT (_MSC_STATUS_ERASEABORTED_DEFAULT << 5) /**< Shifted mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_PCRUNNING (0x1UL << 6) /**< Performance Counters Running */
-#define _MSC_STATUS_PCRUNNING_SHIFT 6 /**< Shift value for MSC_PCRUNNING */
-#define _MSC_STATUS_PCRUNNING_MASK 0x40UL /**< Bit mask for MSC_PCRUNNING */
-#define _MSC_STATUS_PCRUNNING_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_STATUS */
-#define MSC_STATUS_PCRUNNING_DEFAULT (_MSC_STATUS_PCRUNNING_DEFAULT << 6) /**< Shifted mode DEFAULT for MSC_STATUS */
-
-/* Bit fields for MSC IF */
-#define _MSC_IF_RESETVALUE 0x00000000UL /**< Default value for MSC_IF */
-#define _MSC_IF_MASK 0x0000000FUL /**< Mask for MSC_IF */
-#define MSC_IF_ERASE (0x1UL << 0) /**< Erase Done Interrupt Read Flag */
-#define _MSC_IF_ERASE_SHIFT 0 /**< Shift value for MSC_ERASE */
-#define _MSC_IF_ERASE_MASK 0x1UL /**< Bit mask for MSC_ERASE */
-#define _MSC_IF_ERASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IF */
-#define MSC_IF_ERASE_DEFAULT (_MSC_IF_ERASE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_IF */
-#define MSC_IF_WRITE (0x1UL << 1) /**< Write Done Interrupt Read Flag */
-#define _MSC_IF_WRITE_SHIFT 1 /**< Shift value for MSC_WRITE */
-#define _MSC_IF_WRITE_MASK 0x2UL /**< Bit mask for MSC_WRITE */
-#define _MSC_IF_WRITE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IF */
-#define MSC_IF_WRITE_DEFAULT (_MSC_IF_WRITE_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_IF */
-#define MSC_IF_CHOF (0x1UL << 2) /**< Cache Hits Overflow Interrupt Flag */
-#define _MSC_IF_CHOF_SHIFT 2 /**< Shift value for MSC_CHOF */
-#define _MSC_IF_CHOF_MASK 0x4UL /**< Bit mask for MSC_CHOF */
-#define _MSC_IF_CHOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IF */
-#define MSC_IF_CHOF_DEFAULT (_MSC_IF_CHOF_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_IF */
-#define MSC_IF_CMOF (0x1UL << 3) /**< Cache Misses Overflow Interrupt Flag */
-#define _MSC_IF_CMOF_SHIFT 3 /**< Shift value for MSC_CMOF */
-#define _MSC_IF_CMOF_MASK 0x8UL /**< Bit mask for MSC_CMOF */
-#define _MSC_IF_CMOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IF */
-#define MSC_IF_CMOF_DEFAULT (_MSC_IF_CMOF_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_IF */
-
-/* Bit fields for MSC IFS */
-#define _MSC_IFS_RESETVALUE 0x00000000UL /**< Default value for MSC_IFS */
-#define _MSC_IFS_MASK 0x0000000FUL /**< Mask for MSC_IFS */
-#define MSC_IFS_ERASE (0x1UL << 0) /**< Erase Done Interrupt Set */
-#define _MSC_IFS_ERASE_SHIFT 0 /**< Shift value for MSC_ERASE */
-#define _MSC_IFS_ERASE_MASK 0x1UL /**< Bit mask for MSC_ERASE */
-#define _MSC_IFS_ERASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFS */
-#define MSC_IFS_ERASE_DEFAULT (_MSC_IFS_ERASE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_IFS */
-#define MSC_IFS_WRITE (0x1UL << 1) /**< Write Done Interrupt Set */
-#define _MSC_IFS_WRITE_SHIFT 1 /**< Shift value for MSC_WRITE */
-#define _MSC_IFS_WRITE_MASK 0x2UL /**< Bit mask for MSC_WRITE */
-#define _MSC_IFS_WRITE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFS */
-#define MSC_IFS_WRITE_DEFAULT (_MSC_IFS_WRITE_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_IFS */
-#define MSC_IFS_CHOF (0x1UL << 2) /**< Cache Hits Overflow Interrupt Set */
-#define _MSC_IFS_CHOF_SHIFT 2 /**< Shift value for MSC_CHOF */
-#define _MSC_IFS_CHOF_MASK 0x4UL /**< Bit mask for MSC_CHOF */
-#define _MSC_IFS_CHOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFS */
-#define MSC_IFS_CHOF_DEFAULT (_MSC_IFS_CHOF_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_IFS */
-#define MSC_IFS_CMOF (0x1UL << 3) /**< Cache Misses Overflow Interrupt Set */
-#define _MSC_IFS_CMOF_SHIFT 3 /**< Shift value for MSC_CMOF */
-#define _MSC_IFS_CMOF_MASK 0x8UL /**< Bit mask for MSC_CMOF */
-#define _MSC_IFS_CMOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFS */
-#define MSC_IFS_CMOF_DEFAULT (_MSC_IFS_CMOF_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_IFS */
-
-/* Bit fields for MSC IFC */
-#define _MSC_IFC_RESETVALUE 0x00000000UL /**< Default value for MSC_IFC */
-#define _MSC_IFC_MASK 0x0000000FUL /**< Mask for MSC_IFC */
-#define MSC_IFC_ERASE (0x1UL << 0) /**< Erase Done Interrupt Clear */
-#define _MSC_IFC_ERASE_SHIFT 0 /**< Shift value for MSC_ERASE */
-#define _MSC_IFC_ERASE_MASK 0x1UL /**< Bit mask for MSC_ERASE */
-#define _MSC_IFC_ERASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFC */
-#define MSC_IFC_ERASE_DEFAULT (_MSC_IFC_ERASE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_IFC */
-#define MSC_IFC_WRITE (0x1UL << 1) /**< Write Done Interrupt Clear */
-#define _MSC_IFC_WRITE_SHIFT 1 /**< Shift value for MSC_WRITE */
-#define _MSC_IFC_WRITE_MASK 0x2UL /**< Bit mask for MSC_WRITE */
-#define _MSC_IFC_WRITE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFC */
-#define MSC_IFC_WRITE_DEFAULT (_MSC_IFC_WRITE_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_IFC */
-#define MSC_IFC_CHOF (0x1UL << 2) /**< Cache Hits Overflow Interrupt Clear */
-#define _MSC_IFC_CHOF_SHIFT 2 /**< Shift value for MSC_CHOF */
-#define _MSC_IFC_CHOF_MASK 0x4UL /**< Bit mask for MSC_CHOF */
-#define _MSC_IFC_CHOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFC */
-#define MSC_IFC_CHOF_DEFAULT (_MSC_IFC_CHOF_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_IFC */
-#define MSC_IFC_CMOF (0x1UL << 3) /**< Cache Misses Overflow Interrupt Clear */
-#define _MSC_IFC_CMOF_SHIFT 3 /**< Shift value for MSC_CMOF */
-#define _MSC_IFC_CMOF_MASK 0x8UL /**< Bit mask for MSC_CMOF */
-#define _MSC_IFC_CMOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IFC */
-#define MSC_IFC_CMOF_DEFAULT (_MSC_IFC_CMOF_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_IFC */
-
-/* Bit fields for MSC IEN */
-#define _MSC_IEN_RESETVALUE 0x00000000UL /**< Default value for MSC_IEN */
-#define _MSC_IEN_MASK 0x0000000FUL /**< Mask for MSC_IEN */
-#define MSC_IEN_ERASE (0x1UL << 0) /**< Erase Done Interrupt Enable */
-#define _MSC_IEN_ERASE_SHIFT 0 /**< Shift value for MSC_ERASE */
-#define _MSC_IEN_ERASE_MASK 0x1UL /**< Bit mask for MSC_ERASE */
-#define _MSC_IEN_ERASE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IEN */
-#define MSC_IEN_ERASE_DEFAULT (_MSC_IEN_ERASE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_IEN */
-#define MSC_IEN_WRITE (0x1UL << 1) /**< Write Done Interrupt Enable */
-#define _MSC_IEN_WRITE_SHIFT 1 /**< Shift value for MSC_WRITE */
-#define _MSC_IEN_WRITE_MASK 0x2UL /**< Bit mask for MSC_WRITE */
-#define _MSC_IEN_WRITE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IEN */
-#define MSC_IEN_WRITE_DEFAULT (_MSC_IEN_WRITE_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_IEN */
-#define MSC_IEN_CHOF (0x1UL << 2) /**< Cache Hits Overflow Interrupt Enable */
-#define _MSC_IEN_CHOF_SHIFT 2 /**< Shift value for MSC_CHOF */
-#define _MSC_IEN_CHOF_MASK 0x4UL /**< Bit mask for MSC_CHOF */
-#define _MSC_IEN_CHOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IEN */
-#define MSC_IEN_CHOF_DEFAULT (_MSC_IEN_CHOF_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_IEN */
-#define MSC_IEN_CMOF (0x1UL << 3) /**< Cache Misses Overflow Interrupt Enable */
-#define _MSC_IEN_CMOF_SHIFT 3 /**< Shift value for MSC_CMOF */
-#define _MSC_IEN_CMOF_MASK 0x8UL /**< Bit mask for MSC_CMOF */
-#define _MSC_IEN_CMOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IEN */
-#define MSC_IEN_CMOF_DEFAULT (_MSC_IEN_CMOF_DEFAULT << 3) /**< Shifted mode DEFAULT for MSC_IEN */
-
-/* Bit fields for MSC LOCK */
-#define _MSC_LOCK_RESETVALUE 0x00000000UL /**< Default value for MSC_LOCK */
-#define _MSC_LOCK_MASK 0x0000FFFFUL /**< Mask for MSC_LOCK */
-#define _MSC_LOCK_LOCKKEY_SHIFT 0 /**< Shift value for MSC_LOCKKEY */
-#define _MSC_LOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for MSC_LOCKKEY */
-#define _MSC_LOCK_LOCKKEY_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_LOCK */
-#define _MSC_LOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for MSC_LOCK */
-#define _MSC_LOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for MSC_LOCK */
-#define _MSC_LOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for MSC_LOCK */
-#define _MSC_LOCK_LOCKKEY_UNLOCK 0x00001B71UL /**< Mode UNLOCK for MSC_LOCK */
-#define MSC_LOCK_LOCKKEY_DEFAULT (_MSC_LOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_LOCK */
-#define MSC_LOCK_LOCKKEY_LOCK (_MSC_LOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for MSC_LOCK */
-#define MSC_LOCK_LOCKKEY_UNLOCKED (_MSC_LOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for MSC_LOCK */
-#define MSC_LOCK_LOCKKEY_LOCKED (_MSC_LOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for MSC_LOCK */
-#define MSC_LOCK_LOCKKEY_UNLOCK (_MSC_LOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for MSC_LOCK */
-
-/* Bit fields for MSC CMD */
-#define _MSC_CMD_RESETVALUE 0x00000000UL /**< Default value for MSC_CMD */
-#define _MSC_CMD_MASK 0x00000007UL /**< Mask for MSC_CMD */
-#define MSC_CMD_INVCACHE (0x1UL << 0) /**< Invalidate Instruction Cache */
-#define _MSC_CMD_INVCACHE_SHIFT 0 /**< Shift value for MSC_INVCACHE */
-#define _MSC_CMD_INVCACHE_MASK 0x1UL /**< Bit mask for MSC_INVCACHE */
-#define _MSC_CMD_INVCACHE_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_CMD */
-#define MSC_CMD_INVCACHE_DEFAULT (_MSC_CMD_INVCACHE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_CMD */
-#define MSC_CMD_STARTPC (0x1UL << 1) /**< Start Performance Counters */
-#define _MSC_CMD_STARTPC_SHIFT 1 /**< Shift value for MSC_STARTPC */
-#define _MSC_CMD_STARTPC_MASK 0x2UL /**< Bit mask for MSC_STARTPC */
-#define _MSC_CMD_STARTPC_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_CMD */
-#define MSC_CMD_STARTPC_DEFAULT (_MSC_CMD_STARTPC_DEFAULT << 1) /**< Shifted mode DEFAULT for MSC_CMD */
-#define MSC_CMD_STOPPC (0x1UL << 2) /**< Stop Performance Counters */
-#define _MSC_CMD_STOPPC_SHIFT 2 /**< Shift value for MSC_STOPPC */
-#define _MSC_CMD_STOPPC_MASK 0x4UL /**< Bit mask for MSC_STOPPC */
-#define _MSC_CMD_STOPPC_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_CMD */
-#define MSC_CMD_STOPPC_DEFAULT (_MSC_CMD_STOPPC_DEFAULT << 2) /**< Shifted mode DEFAULT for MSC_CMD */
-
-/* Bit fields for MSC CACHEHITS */
-#define _MSC_CACHEHITS_RESETVALUE 0x00000000UL /**< Default value for MSC_CACHEHITS */
-#define _MSC_CACHEHITS_MASK 0x000FFFFFUL /**< Mask for MSC_CACHEHITS */
-#define _MSC_CACHEHITS_CACHEHITS_SHIFT 0 /**< Shift value for MSC_CACHEHITS */
-#define _MSC_CACHEHITS_CACHEHITS_MASK 0xFFFFFUL /**< Bit mask for MSC_CACHEHITS */
-#define _MSC_CACHEHITS_CACHEHITS_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_CACHEHITS */
-#define MSC_CACHEHITS_CACHEHITS_DEFAULT (_MSC_CACHEHITS_CACHEHITS_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_CACHEHITS */
-
-/* Bit fields for MSC CACHEMISSES */
-#define _MSC_CACHEMISSES_RESETVALUE 0x00000000UL /**< Default value for MSC_CACHEMISSES */
-#define _MSC_CACHEMISSES_MASK 0x000FFFFFUL /**< Mask for MSC_CACHEMISSES */
-#define _MSC_CACHEMISSES_CACHEMISSES_SHIFT 0 /**< Shift value for MSC_CACHEMISSES */
-#define _MSC_CACHEMISSES_CACHEMISSES_MASK 0xFFFFFUL /**< Bit mask for MSC_CACHEMISSES */
-#define _MSC_CACHEMISSES_CACHEMISSES_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_CACHEMISSES */
-#define MSC_CACHEMISSES_CACHEMISSES_DEFAULT (_MSC_CACHEMISSES_CACHEMISSES_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_CACHEMISSES */
-
-/* Bit fields for MSC TIMEBASE */
-#define _MSC_TIMEBASE_RESETVALUE 0x00000010UL /**< Default value for MSC_TIMEBASE */
-#define _MSC_TIMEBASE_MASK 0x0001003FUL /**< Mask for MSC_TIMEBASE */
-#define _MSC_TIMEBASE_BASE_SHIFT 0 /**< Shift value for MSC_BASE */
-#define _MSC_TIMEBASE_BASE_MASK 0x3FUL /**< Bit mask for MSC_BASE */
-#define _MSC_TIMEBASE_BASE_DEFAULT 0x00000010UL /**< Mode DEFAULT for MSC_TIMEBASE */
-#define MSC_TIMEBASE_BASE_DEFAULT (_MSC_TIMEBASE_BASE_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_TIMEBASE */
-#define MSC_TIMEBASE_PERIOD (0x1UL << 16) /**< Sets the timebase period */
-#define _MSC_TIMEBASE_PERIOD_SHIFT 16 /**< Shift value for MSC_PERIOD */
-#define _MSC_TIMEBASE_PERIOD_MASK 0x10000UL /**< Bit mask for MSC_PERIOD */
-#define _MSC_TIMEBASE_PERIOD_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_TIMEBASE */
-#define _MSC_TIMEBASE_PERIOD_1US 0x00000000UL /**< Mode 1US for MSC_TIMEBASE */
-#define _MSC_TIMEBASE_PERIOD_5US 0x00000001UL /**< Mode 5US for MSC_TIMEBASE */
-#define MSC_TIMEBASE_PERIOD_DEFAULT (_MSC_TIMEBASE_PERIOD_DEFAULT << 16) /**< Shifted mode DEFAULT for MSC_TIMEBASE */
-#define MSC_TIMEBASE_PERIOD_1US (_MSC_TIMEBASE_PERIOD_1US << 16) /**< Shifted mode 1US for MSC_TIMEBASE */
-#define MSC_TIMEBASE_PERIOD_5US (_MSC_TIMEBASE_PERIOD_5US << 16) /**< Shifted mode 5US for MSC_TIMEBASE */
-
-/* Bit fields for MSC MASSLOCK */
-#define _MSC_MASSLOCK_RESETVALUE 0x00000001UL /**< Default value for MSC_MASSLOCK */
-#define _MSC_MASSLOCK_MASK 0x0000FFFFUL /**< Mask for MSC_MASSLOCK */
-#define _MSC_MASSLOCK_LOCKKEY_SHIFT 0 /**< Shift value for MSC_LOCKKEY */
-#define _MSC_MASSLOCK_LOCKKEY_MASK 0xFFFFUL /**< Bit mask for MSC_LOCKKEY */
-#define _MSC_MASSLOCK_LOCKKEY_LOCK 0x00000000UL /**< Mode LOCK for MSC_MASSLOCK */
-#define _MSC_MASSLOCK_LOCKKEY_UNLOCKED 0x00000000UL /**< Mode UNLOCKED for MSC_MASSLOCK */
-#define _MSC_MASSLOCK_LOCKKEY_DEFAULT 0x00000001UL /**< Mode DEFAULT for MSC_MASSLOCK */
-#define _MSC_MASSLOCK_LOCKKEY_LOCKED 0x00000001UL /**< Mode LOCKED for MSC_MASSLOCK */
-#define _MSC_MASSLOCK_LOCKKEY_UNLOCK 0x0000631AUL /**< Mode UNLOCK for MSC_MASSLOCK */
-#define MSC_MASSLOCK_LOCKKEY_LOCK (_MSC_MASSLOCK_LOCKKEY_LOCK << 0) /**< Shifted mode LOCK for MSC_MASSLOCK */
-#define MSC_MASSLOCK_LOCKKEY_UNLOCKED (_MSC_MASSLOCK_LOCKKEY_UNLOCKED << 0) /**< Shifted mode UNLOCKED for MSC_MASSLOCK */
-#define MSC_MASSLOCK_LOCKKEY_DEFAULT (_MSC_MASSLOCK_LOCKKEY_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_MASSLOCK */
-#define MSC_MASSLOCK_LOCKKEY_LOCKED (_MSC_MASSLOCK_LOCKKEY_LOCKED << 0) /**< Shifted mode LOCKED for MSC_MASSLOCK */
-#define MSC_MASSLOCK_LOCKKEY_UNLOCK (_MSC_MASSLOCK_LOCKKEY_UNLOCK << 0) /**< Shifted mode UNLOCK for MSC_MASSLOCK */
-
-/* Bit fields for MSC IRQLATENCY */
-#define _MSC_IRQLATENCY_RESETVALUE 0x00000000UL /**< Default value for MSC_IRQLATENCY */
-#define _MSC_IRQLATENCY_MASK 0x000000FFUL /**< Mask for MSC_IRQLATENCY */
-#define _MSC_IRQLATENCY_IRQLATENCY_SHIFT 0 /**< Shift value for MSC_IRQLATENCY */
-#define _MSC_IRQLATENCY_IRQLATENCY_MASK 0xFFUL /**< Bit mask for MSC_IRQLATENCY */
-#define _MSC_IRQLATENCY_IRQLATENCY_DEFAULT 0x00000000UL /**< Mode DEFAULT for MSC_IRQLATENCY */
-#define MSC_IRQLATENCY_IRQLATENCY_DEFAULT (_MSC_IRQLATENCY_IRQLATENCY_DEFAULT << 0) /**< Shifted mode DEFAULT for MSC_IRQLATENCY */
-
-/** @} End of group EFM32ZG_MSC */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_pcnt.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_pcnt.h
deleted file mode 100644
index c8454af5cc..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_pcnt.h
+++ /dev/null
@@ -1,475 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_PCNT register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_PCNT
- * @{
- * @brief EFM32ZG_PCNT Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IM uint32_t CNT; /**< Counter Value Register */
- __IM uint32_t TOP; /**< Top Value Register */
- __IOM uint32_t TOPB; /**< Top Value Buffer Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved for future use **/
- __IOM uint32_t AUXCNT; /**< Auxiliary Counter Value Register */
- __IOM uint32_t INPUT; /**< PCNT Input Register */
-} PCNT_TypeDef; /** PCNT Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_PCNT_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for PCNT CTRL */
-#define _PCNT_CTRL_RESETVALUE 0x00000000UL /**< Default value for PCNT_CTRL */
-#define _PCNT_CTRL_MASK 0x7ECCCF7FUL /**< Mask for PCNT_CTRL */
-#define _PCNT_CTRL_MODE_SHIFT 0 /**< Shift value for PCNT_MODE */
-#define _PCNT_CTRL_MODE_MASK 0x3UL /**< Bit mask for PCNT_MODE */
-#define _PCNT_CTRL_MODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_MODE_DISABLE 0x00000000UL /**< Mode DISABLE for PCNT_CTRL */
-#define _PCNT_CTRL_MODE_OVSSINGLE 0x00000001UL /**< Mode OVSSINGLE for PCNT_CTRL */
-#define _PCNT_CTRL_MODE_EXTCLKSINGLE 0x00000002UL /**< Mode EXTCLKSINGLE for PCNT_CTRL */
-#define _PCNT_CTRL_MODE_EXTCLKQUAD 0x00000003UL /**< Mode EXTCLKQUAD for PCNT_CTRL */
-#define PCNT_CTRL_MODE_DEFAULT (_PCNT_CTRL_MODE_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_MODE_DISABLE (_PCNT_CTRL_MODE_DISABLE << 0) /**< Shifted mode DISABLE for PCNT_CTRL */
-#define PCNT_CTRL_MODE_OVSSINGLE (_PCNT_CTRL_MODE_OVSSINGLE << 0) /**< Shifted mode OVSSINGLE for PCNT_CTRL */
-#define PCNT_CTRL_MODE_EXTCLKSINGLE (_PCNT_CTRL_MODE_EXTCLKSINGLE << 0) /**< Shifted mode EXTCLKSINGLE for PCNT_CTRL */
-#define PCNT_CTRL_MODE_EXTCLKQUAD (_PCNT_CTRL_MODE_EXTCLKQUAD << 0) /**< Shifted mode EXTCLKQUAD for PCNT_CTRL */
-#define PCNT_CTRL_CNTDIR (0x1UL << 2) /**< Non-Quadrature Mode Counter Direction Control */
-#define _PCNT_CTRL_CNTDIR_SHIFT 2 /**< Shift value for PCNT_CNTDIR */
-#define _PCNT_CTRL_CNTDIR_MASK 0x4UL /**< Bit mask for PCNT_CNTDIR */
-#define _PCNT_CTRL_CNTDIR_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_CNTDIR_UP 0x00000000UL /**< Mode UP for PCNT_CTRL */
-#define _PCNT_CTRL_CNTDIR_DOWN 0x00000001UL /**< Mode DOWN for PCNT_CTRL */
-#define PCNT_CTRL_CNTDIR_DEFAULT (_PCNT_CTRL_CNTDIR_DEFAULT << 2) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_CNTDIR_UP (_PCNT_CTRL_CNTDIR_UP << 2) /**< Shifted mode UP for PCNT_CTRL */
-#define PCNT_CTRL_CNTDIR_DOWN (_PCNT_CTRL_CNTDIR_DOWN << 2) /**< Shifted mode DOWN for PCNT_CTRL */
-#define PCNT_CTRL_EDGE (0x1UL << 3) /**< Edge Select */
-#define _PCNT_CTRL_EDGE_SHIFT 3 /**< Shift value for PCNT_EDGE */
-#define _PCNT_CTRL_EDGE_MASK 0x8UL /**< Bit mask for PCNT_EDGE */
-#define _PCNT_CTRL_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_EDGE_POS 0x00000000UL /**< Mode POS for PCNT_CTRL */
-#define _PCNT_CTRL_EDGE_NEG 0x00000001UL /**< Mode NEG for PCNT_CTRL */
-#define PCNT_CTRL_EDGE_DEFAULT (_PCNT_CTRL_EDGE_DEFAULT << 3) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_EDGE_POS (_PCNT_CTRL_EDGE_POS << 3) /**< Shifted mode POS for PCNT_CTRL */
-#define PCNT_CTRL_EDGE_NEG (_PCNT_CTRL_EDGE_NEG << 3) /**< Shifted mode NEG for PCNT_CTRL */
-#define PCNT_CTRL_FILT (0x1UL << 4) /**< Enable Digital Pulse Width Filter */
-#define _PCNT_CTRL_FILT_SHIFT 4 /**< Shift value for PCNT_FILT */
-#define _PCNT_CTRL_FILT_MASK 0x10UL /**< Bit mask for PCNT_FILT */
-#define _PCNT_CTRL_FILT_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_FILT_DEFAULT (_PCNT_CTRL_FILT_DEFAULT << 4) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_RSTEN (0x1UL << 5) /**< Enable PCNT Clock Domain Reset */
-#define _PCNT_CTRL_RSTEN_SHIFT 5 /**< Shift value for PCNT_RSTEN */
-#define _PCNT_CTRL_RSTEN_MASK 0x20UL /**< Bit mask for PCNT_RSTEN */
-#define _PCNT_CTRL_RSTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_RSTEN_DEFAULT (_PCNT_CTRL_RSTEN_DEFAULT << 5) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTRSTEN (0x1UL << 6) /**< Enable AUXCNT Reset */
-#define _PCNT_CTRL_AUXCNTRSTEN_SHIFT 6 /**< Shift value for PCNT_AUXCNTRSTEN */
-#define _PCNT_CTRL_AUXCNTRSTEN_MASK 0x40UL /**< Bit mask for PCNT_AUXCNTRSTEN */
-#define _PCNT_CTRL_AUXCNTRSTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTRSTEN_DEFAULT (_PCNT_CTRL_AUXCNTRSTEN_DEFAULT << 6) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_HYST (0x1UL << 8) /**< Enable Hysteresis */
-#define _PCNT_CTRL_HYST_SHIFT 8 /**< Shift value for PCNT_HYST */
-#define _PCNT_CTRL_HYST_MASK 0x100UL /**< Bit mask for PCNT_HYST */
-#define _PCNT_CTRL_HYST_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_HYST_DEFAULT (_PCNT_CTRL_HYST_DEFAULT << 8) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_S1CDIR (0x1UL << 9) /**< Count direction determined by S1 */
-#define _PCNT_CTRL_S1CDIR_SHIFT 9 /**< Shift value for PCNT_S1CDIR */
-#define _PCNT_CTRL_S1CDIR_MASK 0x200UL /**< Bit mask for PCNT_S1CDIR */
-#define _PCNT_CTRL_S1CDIR_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_S1CDIR_DEFAULT (_PCNT_CTRL_S1CDIR_DEFAULT << 9) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_CNTEV_SHIFT 10 /**< Shift value for PCNT_CNTEV */
-#define _PCNT_CTRL_CNTEV_MASK 0xC00UL /**< Bit mask for PCNT_CNTEV */
-#define _PCNT_CTRL_CNTEV_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_CNTEV_BOTH 0x00000000UL /**< Mode BOTH for PCNT_CTRL */
-#define _PCNT_CTRL_CNTEV_UP 0x00000001UL /**< Mode UP for PCNT_CTRL */
-#define _PCNT_CTRL_CNTEV_DOWN 0x00000002UL /**< Mode DOWN for PCNT_CTRL */
-#define _PCNT_CTRL_CNTEV_NONE 0x00000003UL /**< Mode NONE for PCNT_CTRL */
-#define PCNT_CTRL_CNTEV_DEFAULT (_PCNT_CTRL_CNTEV_DEFAULT << 10) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_CNTEV_BOTH (_PCNT_CTRL_CNTEV_BOTH << 10) /**< Shifted mode BOTH for PCNT_CTRL */
-#define PCNT_CTRL_CNTEV_UP (_PCNT_CTRL_CNTEV_UP << 10) /**< Shifted mode UP for PCNT_CTRL */
-#define PCNT_CTRL_CNTEV_DOWN (_PCNT_CTRL_CNTEV_DOWN << 10) /**< Shifted mode DOWN for PCNT_CTRL */
-#define PCNT_CTRL_CNTEV_NONE (_PCNT_CTRL_CNTEV_NONE << 10) /**< Shifted mode NONE for PCNT_CTRL */
-#define _PCNT_CTRL_AUXCNTEV_SHIFT 14 /**< Shift value for PCNT_AUXCNTEV */
-#define _PCNT_CTRL_AUXCNTEV_MASK 0xC000UL /**< Bit mask for PCNT_AUXCNTEV */
-#define _PCNT_CTRL_AUXCNTEV_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_AUXCNTEV_NONE 0x00000000UL /**< Mode NONE for PCNT_CTRL */
-#define _PCNT_CTRL_AUXCNTEV_UP 0x00000001UL /**< Mode UP for PCNT_CTRL */
-#define _PCNT_CTRL_AUXCNTEV_DOWN 0x00000002UL /**< Mode DOWN for PCNT_CTRL */
-#define _PCNT_CTRL_AUXCNTEV_BOTH 0x00000003UL /**< Mode BOTH for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTEV_DEFAULT (_PCNT_CTRL_AUXCNTEV_DEFAULT << 14) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTEV_NONE (_PCNT_CTRL_AUXCNTEV_NONE << 14) /**< Shifted mode NONE for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTEV_UP (_PCNT_CTRL_AUXCNTEV_UP << 14) /**< Shifted mode UP for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTEV_DOWN (_PCNT_CTRL_AUXCNTEV_DOWN << 14) /**< Shifted mode DOWN for PCNT_CTRL */
-#define PCNT_CTRL_AUXCNTEV_BOTH (_PCNT_CTRL_AUXCNTEV_BOTH << 14) /**< Shifted mode BOTH for PCNT_CTRL */
-#define _PCNT_CTRL_TCCMODE_SHIFT 18 /**< Shift value for PCNT_TCCMODE */
-#define _PCNT_CTRL_TCCMODE_MASK 0xC0000UL /**< Bit mask for PCNT_TCCMODE */
-#define _PCNT_CTRL_TCCMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_TCCMODE_DISABLED 0x00000000UL /**< Mode DISABLED for PCNT_CTRL */
-#define _PCNT_CTRL_TCCMODE_LFA 0x00000001UL /**< Mode LFA for PCNT_CTRL */
-#define _PCNT_CTRL_TCCMODE_PRS 0x00000002UL /**< Mode PRS for PCNT_CTRL */
-#define PCNT_CTRL_TCCMODE_DEFAULT (_PCNT_CTRL_TCCMODE_DEFAULT << 18) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_TCCMODE_DISABLED (_PCNT_CTRL_TCCMODE_DISABLED << 18) /**< Shifted mode DISABLED for PCNT_CTRL */
-#define PCNT_CTRL_TCCMODE_LFA (_PCNT_CTRL_TCCMODE_LFA << 18) /**< Shifted mode LFA for PCNT_CTRL */
-#define PCNT_CTRL_TCCMODE_PRS (_PCNT_CTRL_TCCMODE_PRS << 18) /**< Shifted mode PRS for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRESC_SHIFT 22 /**< Shift value for PCNT_TCCPRESC */
-#define _PCNT_CTRL_TCCPRESC_MASK 0xC00000UL /**< Bit mask for PCNT_TCCPRESC */
-#define _PCNT_CTRL_TCCPRESC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRESC_DIV1 0x00000000UL /**< Mode DIV1 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRESC_DIV2 0x00000001UL /**< Mode DIV2 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRESC_DIV4 0x00000002UL /**< Mode DIV4 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRESC_DIV8 0x00000003UL /**< Mode DIV8 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRESC_DEFAULT (_PCNT_CTRL_TCCPRESC_DEFAULT << 22) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRESC_DIV1 (_PCNT_CTRL_TCCPRESC_DIV1 << 22) /**< Shifted mode DIV1 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRESC_DIV2 (_PCNT_CTRL_TCCPRESC_DIV2 << 22) /**< Shifted mode DIV2 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRESC_DIV4 (_PCNT_CTRL_TCCPRESC_DIV4 << 22) /**< Shifted mode DIV4 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRESC_DIV8 (_PCNT_CTRL_TCCPRESC_DIV8 << 22) /**< Shifted mode DIV8 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCCOMP_SHIFT 25 /**< Shift value for PCNT_TCCCOMP */
-#define _PCNT_CTRL_TCCCOMP_MASK 0x6000000UL /**< Bit mask for PCNT_TCCCOMP */
-#define _PCNT_CTRL_TCCCOMP_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_TCCCOMP_LTOE 0x00000000UL /**< Mode LTOE for PCNT_CTRL */
-#define _PCNT_CTRL_TCCCOMP_GTOE 0x00000001UL /**< Mode GTOE for PCNT_CTRL */
-#define _PCNT_CTRL_TCCCOMP_RANGE 0x00000002UL /**< Mode RANGE for PCNT_CTRL */
-#define PCNT_CTRL_TCCCOMP_DEFAULT (_PCNT_CTRL_TCCCOMP_DEFAULT << 25) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_TCCCOMP_LTOE (_PCNT_CTRL_TCCCOMP_LTOE << 25) /**< Shifted mode LTOE for PCNT_CTRL */
-#define PCNT_CTRL_TCCCOMP_GTOE (_PCNT_CTRL_TCCCOMP_GTOE << 25) /**< Shifted mode GTOE for PCNT_CTRL */
-#define PCNT_CTRL_TCCCOMP_RANGE (_PCNT_CTRL_TCCCOMP_RANGE << 25) /**< Shifted mode RANGE for PCNT_CTRL */
-#define PCNT_CTRL_PRSGATEEN (0x1UL << 27) /**< PRS gate enable */
-#define _PCNT_CTRL_PRSGATEEN_SHIFT 27 /**< Shift value for PCNT_PRSGATEEN */
-#define _PCNT_CTRL_PRSGATEEN_MASK 0x8000000UL /**< Bit mask for PCNT_PRSGATEEN */
-#define _PCNT_CTRL_PRSGATEEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_PRSGATEEN_DEFAULT (_PCNT_CTRL_PRSGATEEN_DEFAULT << 27) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSPOL (0x1UL << 28) /**< TCC PRS polarity select */
-#define _PCNT_CTRL_TCCPRSPOL_SHIFT 28 /**< Shift value for PCNT_TCCPRSPOL */
-#define _PCNT_CTRL_TCCPRSPOL_MASK 0x10000000UL /**< Bit mask for PCNT_TCCPRSPOL */
-#define _PCNT_CTRL_TCCPRSPOL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSPOL_RISING 0x00000000UL /**< Mode RISING for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSPOL_FALLING 0x00000001UL /**< Mode FALLING for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSPOL_DEFAULT (_PCNT_CTRL_TCCPRSPOL_DEFAULT << 28) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSPOL_RISING (_PCNT_CTRL_TCCPRSPOL_RISING << 28) /**< Shifted mode RISING for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSPOL_FALLING (_PCNT_CTRL_TCCPRSPOL_FALLING << 28) /**< Shifted mode FALLING for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSSEL_SHIFT 29 /**< Shift value for PCNT_TCCPRSSEL */
-#define _PCNT_CTRL_TCCPRSSEL_MASK 0x60000000UL /**< Bit mask for PCNT_TCCPRSSEL */
-#define _PCNT_CTRL_TCCPRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for PCNT_CTRL */
-#define _PCNT_CTRL_TCCPRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSSEL_DEFAULT (_PCNT_CTRL_TCCPRSSEL_DEFAULT << 29) /**< Shifted mode DEFAULT for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSSEL_PRSCH0 (_PCNT_CTRL_TCCPRSSEL_PRSCH0 << 29) /**< Shifted mode PRSCH0 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSSEL_PRSCH1 (_PCNT_CTRL_TCCPRSSEL_PRSCH1 << 29) /**< Shifted mode PRSCH1 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSSEL_PRSCH2 (_PCNT_CTRL_TCCPRSSEL_PRSCH2 << 29) /**< Shifted mode PRSCH2 for PCNT_CTRL */
-#define PCNT_CTRL_TCCPRSSEL_PRSCH3 (_PCNT_CTRL_TCCPRSSEL_PRSCH3 << 29) /**< Shifted mode PRSCH3 for PCNT_CTRL */
-
-/* Bit fields for PCNT CMD */
-#define _PCNT_CMD_RESETVALUE 0x00000000UL /**< Default value for PCNT_CMD */
-#define _PCNT_CMD_MASK 0x00000003UL /**< Mask for PCNT_CMD */
-#define PCNT_CMD_LCNTIM (0x1UL << 0) /**< Load CNT Immediately */
-#define _PCNT_CMD_LCNTIM_SHIFT 0 /**< Shift value for PCNT_LCNTIM */
-#define _PCNT_CMD_LCNTIM_MASK 0x1UL /**< Bit mask for PCNT_LCNTIM */
-#define _PCNT_CMD_LCNTIM_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CMD */
-#define PCNT_CMD_LCNTIM_DEFAULT (_PCNT_CMD_LCNTIM_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_CMD */
-#define PCNT_CMD_LTOPBIM (0x1UL << 1) /**< Load TOPB Immediately */
-#define _PCNT_CMD_LTOPBIM_SHIFT 1 /**< Shift value for PCNT_LTOPBIM */
-#define _PCNT_CMD_LTOPBIM_MASK 0x2UL /**< Bit mask for PCNT_LTOPBIM */
-#define _PCNT_CMD_LTOPBIM_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CMD */
-#define PCNT_CMD_LTOPBIM_DEFAULT (_PCNT_CMD_LTOPBIM_DEFAULT << 1) /**< Shifted mode DEFAULT for PCNT_CMD */
-
-/* Bit fields for PCNT STATUS */
-#define _PCNT_STATUS_RESETVALUE 0x00000000UL /**< Default value for PCNT_STATUS */
-#define _PCNT_STATUS_MASK 0x00000001UL /**< Mask for PCNT_STATUS */
-#define PCNT_STATUS_DIR (0x1UL << 0) /**< Current Counter Direction */
-#define _PCNT_STATUS_DIR_SHIFT 0 /**< Shift value for PCNT_DIR */
-#define _PCNT_STATUS_DIR_MASK 0x1UL /**< Bit mask for PCNT_DIR */
-#define _PCNT_STATUS_DIR_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_STATUS */
-#define _PCNT_STATUS_DIR_UP 0x00000000UL /**< Mode UP for PCNT_STATUS */
-#define _PCNT_STATUS_DIR_DOWN 0x00000001UL /**< Mode DOWN for PCNT_STATUS */
-#define PCNT_STATUS_DIR_DEFAULT (_PCNT_STATUS_DIR_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_STATUS */
-#define PCNT_STATUS_DIR_UP (_PCNT_STATUS_DIR_UP << 0) /**< Shifted mode UP for PCNT_STATUS */
-#define PCNT_STATUS_DIR_DOWN (_PCNT_STATUS_DIR_DOWN << 0) /**< Shifted mode DOWN for PCNT_STATUS */
-
-/* Bit fields for PCNT CNT */
-#define _PCNT_CNT_RESETVALUE 0x00000000UL /**< Default value for PCNT_CNT */
-#define _PCNT_CNT_MASK 0x0000FFFFUL /**< Mask for PCNT_CNT */
-#define _PCNT_CNT_CNT_SHIFT 0 /**< Shift value for PCNT_CNT */
-#define _PCNT_CNT_CNT_MASK 0xFFFFUL /**< Bit mask for PCNT_CNT */
-#define _PCNT_CNT_CNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_CNT */
-#define PCNT_CNT_CNT_DEFAULT (_PCNT_CNT_CNT_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_CNT */
-
-/* Bit fields for PCNT TOP */
-#define _PCNT_TOP_RESETVALUE 0x000000FFUL /**< Default value for PCNT_TOP */
-#define _PCNT_TOP_MASK 0x0000FFFFUL /**< Mask for PCNT_TOP */
-#define _PCNT_TOP_TOP_SHIFT 0 /**< Shift value for PCNT_TOP */
-#define _PCNT_TOP_TOP_MASK 0xFFFFUL /**< Bit mask for PCNT_TOP */
-#define _PCNT_TOP_TOP_DEFAULT 0x000000FFUL /**< Mode DEFAULT for PCNT_TOP */
-#define PCNT_TOP_TOP_DEFAULT (_PCNT_TOP_TOP_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_TOP */
-
-/* Bit fields for PCNT TOPB */
-#define _PCNT_TOPB_RESETVALUE 0x000000FFUL /**< Default value for PCNT_TOPB */
-#define _PCNT_TOPB_MASK 0x0000FFFFUL /**< Mask for PCNT_TOPB */
-#define _PCNT_TOPB_TOPB_SHIFT 0 /**< Shift value for PCNT_TOPB */
-#define _PCNT_TOPB_TOPB_MASK 0xFFFFUL /**< Bit mask for PCNT_TOPB */
-#define _PCNT_TOPB_TOPB_DEFAULT 0x000000FFUL /**< Mode DEFAULT for PCNT_TOPB */
-#define PCNT_TOPB_TOPB_DEFAULT (_PCNT_TOPB_TOPB_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_TOPB */
-
-/* Bit fields for PCNT IF */
-#define _PCNT_IF_RESETVALUE 0x00000000UL /**< Default value for PCNT_IF */
-#define _PCNT_IF_MASK 0x0000001FUL /**< Mask for PCNT_IF */
-#define PCNT_IF_UF (0x1UL << 0) /**< Underflow Interrupt Read Flag */
-#define _PCNT_IF_UF_SHIFT 0 /**< Shift value for PCNT_UF */
-#define _PCNT_IF_UF_MASK 0x1UL /**< Bit mask for PCNT_UF */
-#define _PCNT_IF_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IF */
-#define PCNT_IF_UF_DEFAULT (_PCNT_IF_UF_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_IF */
-#define PCNT_IF_OF (0x1UL << 1) /**< Overflow Interrupt Read Flag */
-#define _PCNT_IF_OF_SHIFT 1 /**< Shift value for PCNT_OF */
-#define _PCNT_IF_OF_MASK 0x2UL /**< Bit mask for PCNT_OF */
-#define _PCNT_IF_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IF */
-#define PCNT_IF_OF_DEFAULT (_PCNT_IF_OF_DEFAULT << 1) /**< Shifted mode DEFAULT for PCNT_IF */
-#define PCNT_IF_DIRCNG (0x1UL << 2) /**< Direction Change Detect Interrupt Flag */
-#define _PCNT_IF_DIRCNG_SHIFT 2 /**< Shift value for PCNT_DIRCNG */
-#define _PCNT_IF_DIRCNG_MASK 0x4UL /**< Bit mask for PCNT_DIRCNG */
-#define _PCNT_IF_DIRCNG_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IF */
-#define PCNT_IF_DIRCNG_DEFAULT (_PCNT_IF_DIRCNG_DEFAULT << 2) /**< Shifted mode DEFAULT for PCNT_IF */
-#define PCNT_IF_AUXOF (0x1UL << 3) /**< Overflow Interrupt Read Flag */
-#define _PCNT_IF_AUXOF_SHIFT 3 /**< Shift value for PCNT_AUXOF */
-#define _PCNT_IF_AUXOF_MASK 0x8UL /**< Bit mask for PCNT_AUXOF */
-#define _PCNT_IF_AUXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IF */
-#define PCNT_IF_AUXOF_DEFAULT (_PCNT_IF_AUXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for PCNT_IF */
-#define PCNT_IF_TCC (0x1UL << 4) /**< Triggered compare Interrupt Read Flag */
-#define _PCNT_IF_TCC_SHIFT 4 /**< Shift value for PCNT_TCC */
-#define _PCNT_IF_TCC_MASK 0x10UL /**< Bit mask for PCNT_TCC */
-#define _PCNT_IF_TCC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IF */
-#define PCNT_IF_TCC_DEFAULT (_PCNT_IF_TCC_DEFAULT << 4) /**< Shifted mode DEFAULT for PCNT_IF */
-
-/* Bit fields for PCNT IFS */
-#define _PCNT_IFS_RESETVALUE 0x00000000UL /**< Default value for PCNT_IFS */
-#define _PCNT_IFS_MASK 0x0000001FUL /**< Mask for PCNT_IFS */
-#define PCNT_IFS_UF (0x1UL << 0) /**< Underflow interrupt set */
-#define _PCNT_IFS_UF_SHIFT 0 /**< Shift value for PCNT_UF */
-#define _PCNT_IFS_UF_MASK 0x1UL /**< Bit mask for PCNT_UF */
-#define _PCNT_IFS_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_UF_DEFAULT (_PCNT_IFS_UF_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_OF (0x1UL << 1) /**< Overflow Interrupt Set */
-#define _PCNT_IFS_OF_SHIFT 1 /**< Shift value for PCNT_OF */
-#define _PCNT_IFS_OF_MASK 0x2UL /**< Bit mask for PCNT_OF */
-#define _PCNT_IFS_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_OF_DEFAULT (_PCNT_IFS_OF_DEFAULT << 1) /**< Shifted mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_DIRCNG (0x1UL << 2) /**< Direction Change Detect Interrupt Set */
-#define _PCNT_IFS_DIRCNG_SHIFT 2 /**< Shift value for PCNT_DIRCNG */
-#define _PCNT_IFS_DIRCNG_MASK 0x4UL /**< Bit mask for PCNT_DIRCNG */
-#define _PCNT_IFS_DIRCNG_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_DIRCNG_DEFAULT (_PCNT_IFS_DIRCNG_DEFAULT << 2) /**< Shifted mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_AUXOF (0x1UL << 3) /**< Auxiliary Overflow Interrupt Set */
-#define _PCNT_IFS_AUXOF_SHIFT 3 /**< Shift value for PCNT_AUXOF */
-#define _PCNT_IFS_AUXOF_MASK 0x8UL /**< Bit mask for PCNT_AUXOF */
-#define _PCNT_IFS_AUXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_AUXOF_DEFAULT (_PCNT_IFS_AUXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_TCC (0x1UL << 4) /**< Triggered compare Interrupt Set */
-#define _PCNT_IFS_TCC_SHIFT 4 /**< Shift value for PCNT_TCC */
-#define _PCNT_IFS_TCC_MASK 0x10UL /**< Bit mask for PCNT_TCC */
-#define _PCNT_IFS_TCC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFS */
-#define PCNT_IFS_TCC_DEFAULT (_PCNT_IFS_TCC_DEFAULT << 4) /**< Shifted mode DEFAULT for PCNT_IFS */
-
-/* Bit fields for PCNT IFC */
-#define _PCNT_IFC_RESETVALUE 0x00000000UL /**< Default value for PCNT_IFC */
-#define _PCNT_IFC_MASK 0x0000001FUL /**< Mask for PCNT_IFC */
-#define PCNT_IFC_UF (0x1UL << 0) /**< Underflow Interrupt Clear */
-#define _PCNT_IFC_UF_SHIFT 0 /**< Shift value for PCNT_UF */
-#define _PCNT_IFC_UF_MASK 0x1UL /**< Bit mask for PCNT_UF */
-#define _PCNT_IFC_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_UF_DEFAULT (_PCNT_IFC_UF_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_OF (0x1UL << 1) /**< Overflow Interrupt Clear */
-#define _PCNT_IFC_OF_SHIFT 1 /**< Shift value for PCNT_OF */
-#define _PCNT_IFC_OF_MASK 0x2UL /**< Bit mask for PCNT_OF */
-#define _PCNT_IFC_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_OF_DEFAULT (_PCNT_IFC_OF_DEFAULT << 1) /**< Shifted mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_DIRCNG (0x1UL << 2) /**< Direction Change Detect Interrupt Clear */
-#define _PCNT_IFC_DIRCNG_SHIFT 2 /**< Shift value for PCNT_DIRCNG */
-#define _PCNT_IFC_DIRCNG_MASK 0x4UL /**< Bit mask for PCNT_DIRCNG */
-#define _PCNT_IFC_DIRCNG_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_DIRCNG_DEFAULT (_PCNT_IFC_DIRCNG_DEFAULT << 2) /**< Shifted mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_AUXOF (0x1UL << 3) /**< Auxiliary Overflow Interrupt Clear */
-#define _PCNT_IFC_AUXOF_SHIFT 3 /**< Shift value for PCNT_AUXOF */
-#define _PCNT_IFC_AUXOF_MASK 0x8UL /**< Bit mask for PCNT_AUXOF */
-#define _PCNT_IFC_AUXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_AUXOF_DEFAULT (_PCNT_IFC_AUXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_TCC (0x1UL << 4) /**< Triggered compare Interrupt Clear */
-#define _PCNT_IFC_TCC_SHIFT 4 /**< Shift value for PCNT_TCC */
-#define _PCNT_IFC_TCC_MASK 0x10UL /**< Bit mask for PCNT_TCC */
-#define _PCNT_IFC_TCC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IFC */
-#define PCNT_IFC_TCC_DEFAULT (_PCNT_IFC_TCC_DEFAULT << 4) /**< Shifted mode DEFAULT for PCNT_IFC */
-
-/* Bit fields for PCNT IEN */
-#define _PCNT_IEN_RESETVALUE 0x00000000UL /**< Default value for PCNT_IEN */
-#define _PCNT_IEN_MASK 0x0000001FUL /**< Mask for PCNT_IEN */
-#define PCNT_IEN_UF (0x1UL << 0) /**< Underflow Interrupt Enable */
-#define _PCNT_IEN_UF_SHIFT 0 /**< Shift value for PCNT_UF */
-#define _PCNT_IEN_UF_MASK 0x1UL /**< Bit mask for PCNT_UF */
-#define _PCNT_IEN_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_UF_DEFAULT (_PCNT_IEN_UF_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_OF (0x1UL << 1) /**< Overflow Interrupt Enable */
-#define _PCNT_IEN_OF_SHIFT 1 /**< Shift value for PCNT_OF */
-#define _PCNT_IEN_OF_MASK 0x2UL /**< Bit mask for PCNT_OF */
-#define _PCNT_IEN_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_OF_DEFAULT (_PCNT_IEN_OF_DEFAULT << 1) /**< Shifted mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_DIRCNG (0x1UL << 2) /**< Direction Change Detect Interrupt Enable */
-#define _PCNT_IEN_DIRCNG_SHIFT 2 /**< Shift value for PCNT_DIRCNG */
-#define _PCNT_IEN_DIRCNG_MASK 0x4UL /**< Bit mask for PCNT_DIRCNG */
-#define _PCNT_IEN_DIRCNG_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_DIRCNG_DEFAULT (_PCNT_IEN_DIRCNG_DEFAULT << 2) /**< Shifted mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_AUXOF (0x1UL << 3) /**< Auxiliary Overflow Interrupt Enable */
-#define _PCNT_IEN_AUXOF_SHIFT 3 /**< Shift value for PCNT_AUXOF */
-#define _PCNT_IEN_AUXOF_MASK 0x8UL /**< Bit mask for PCNT_AUXOF */
-#define _PCNT_IEN_AUXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_AUXOF_DEFAULT (_PCNT_IEN_AUXOF_DEFAULT << 3) /**< Shifted mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_TCC (0x1UL << 4) /**< Triggered compare Interrupt Enable */
-#define _PCNT_IEN_TCC_SHIFT 4 /**< Shift value for PCNT_TCC */
-#define _PCNT_IEN_TCC_MASK 0x10UL /**< Bit mask for PCNT_TCC */
-#define _PCNT_IEN_TCC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_IEN */
-#define PCNT_IEN_TCC_DEFAULT (_PCNT_IEN_TCC_DEFAULT << 4) /**< Shifted mode DEFAULT for PCNT_IEN */
-
-/* Bit fields for PCNT ROUTE */
-#define _PCNT_ROUTE_RESETVALUE 0x00000000UL /**< Default value for PCNT_ROUTE */
-#define _PCNT_ROUTE_MASK 0x00000700UL /**< Mask for PCNT_ROUTE */
-#define _PCNT_ROUTE_LOCATION_SHIFT 8 /**< Shift value for PCNT_LOCATION */
-#define _PCNT_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for PCNT_LOCATION */
-#define _PCNT_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for PCNT_ROUTE */
-#define _PCNT_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_ROUTE */
-#define _PCNT_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for PCNT_ROUTE */
-#define _PCNT_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for PCNT_ROUTE */
-#define _PCNT_ROUTE_LOCATION_LOC3 0x00000003UL /**< Mode LOC3 for PCNT_ROUTE */
-#define PCNT_ROUTE_LOCATION_LOC0 (_PCNT_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for PCNT_ROUTE */
-#define PCNT_ROUTE_LOCATION_DEFAULT (_PCNT_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for PCNT_ROUTE */
-#define PCNT_ROUTE_LOCATION_LOC1 (_PCNT_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for PCNT_ROUTE */
-#define PCNT_ROUTE_LOCATION_LOC2 (_PCNT_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for PCNT_ROUTE */
-#define PCNT_ROUTE_LOCATION_LOC3 (_PCNT_ROUTE_LOCATION_LOC3 << 8) /**< Shifted mode LOC3 for PCNT_ROUTE */
-
-/* Bit fields for PCNT FREEZE */
-#define _PCNT_FREEZE_RESETVALUE 0x00000000UL /**< Default value for PCNT_FREEZE */
-#define _PCNT_FREEZE_MASK 0x00000001UL /**< Mask for PCNT_FREEZE */
-#define PCNT_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _PCNT_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for PCNT_REGFREEZE */
-#define _PCNT_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for PCNT_REGFREEZE */
-#define _PCNT_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_FREEZE */
-#define _PCNT_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for PCNT_FREEZE */
-#define _PCNT_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for PCNT_FREEZE */
-#define PCNT_FREEZE_REGFREEZE_DEFAULT (_PCNT_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_FREEZE */
-#define PCNT_FREEZE_REGFREEZE_UPDATE (_PCNT_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for PCNT_FREEZE */
-#define PCNT_FREEZE_REGFREEZE_FREEZE (_PCNT_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for PCNT_FREEZE */
-
-/* Bit fields for PCNT SYNCBUSY */
-#define _PCNT_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for PCNT_SYNCBUSY */
-#define _PCNT_SYNCBUSY_MASK 0x00000007UL /**< Mask for PCNT_SYNCBUSY */
-#define PCNT_SYNCBUSY_CTRL (0x1UL << 0) /**< CTRL Register Busy */
-#define _PCNT_SYNCBUSY_CTRL_SHIFT 0 /**< Shift value for PCNT_CTRL */
-#define _PCNT_SYNCBUSY_CTRL_MASK 0x1UL /**< Bit mask for PCNT_CTRL */
-#define _PCNT_SYNCBUSY_CTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_SYNCBUSY */
-#define PCNT_SYNCBUSY_CTRL_DEFAULT (_PCNT_SYNCBUSY_CTRL_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_SYNCBUSY */
-#define PCNT_SYNCBUSY_CMD (0x1UL << 1) /**< CMD Register Busy */
-#define _PCNT_SYNCBUSY_CMD_SHIFT 1 /**< Shift value for PCNT_CMD */
-#define _PCNT_SYNCBUSY_CMD_MASK 0x2UL /**< Bit mask for PCNT_CMD */
-#define _PCNT_SYNCBUSY_CMD_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_SYNCBUSY */
-#define PCNT_SYNCBUSY_CMD_DEFAULT (_PCNT_SYNCBUSY_CMD_DEFAULT << 1) /**< Shifted mode DEFAULT for PCNT_SYNCBUSY */
-#define PCNT_SYNCBUSY_TOPB (0x1UL << 2) /**< TOPB Register Busy */
-#define _PCNT_SYNCBUSY_TOPB_SHIFT 2 /**< Shift value for PCNT_TOPB */
-#define _PCNT_SYNCBUSY_TOPB_MASK 0x4UL /**< Bit mask for PCNT_TOPB */
-#define _PCNT_SYNCBUSY_TOPB_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_SYNCBUSY */
-#define PCNT_SYNCBUSY_TOPB_DEFAULT (_PCNT_SYNCBUSY_TOPB_DEFAULT << 2) /**< Shifted mode DEFAULT for PCNT_SYNCBUSY */
-
-/* Bit fields for PCNT AUXCNT */
-#define _PCNT_AUXCNT_RESETVALUE 0x00000000UL /**< Default value for PCNT_AUXCNT */
-#define _PCNT_AUXCNT_MASK 0x0000FFFFUL /**< Mask for PCNT_AUXCNT */
-#define _PCNT_AUXCNT_AUXCNT_SHIFT 0 /**< Shift value for PCNT_AUXCNT */
-#define _PCNT_AUXCNT_AUXCNT_MASK 0xFFFFUL /**< Bit mask for PCNT_AUXCNT */
-#define _PCNT_AUXCNT_AUXCNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_AUXCNT */
-#define PCNT_AUXCNT_AUXCNT_DEFAULT (_PCNT_AUXCNT_AUXCNT_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_AUXCNT */
-
-/* Bit fields for PCNT INPUT */
-#define _PCNT_INPUT_RESETVALUE 0x00000000UL /**< Default value for PCNT_INPUT */
-#define _PCNT_INPUT_MASK 0x000004D3UL /**< Mask for PCNT_INPUT */
-#define _PCNT_INPUT_S0PRSSEL_SHIFT 0 /**< Shift value for PCNT_S0PRSSEL */
-#define _PCNT_INPUT_S0PRSSEL_MASK 0x3UL /**< Bit mask for PCNT_S0PRSSEL */
-#define _PCNT_INPUT_S0PRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_INPUT */
-#define _PCNT_INPUT_S0PRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for PCNT_INPUT */
-#define _PCNT_INPUT_S0PRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for PCNT_INPUT */
-#define _PCNT_INPUT_S0PRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for PCNT_INPUT */
-#define _PCNT_INPUT_S0PRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSSEL_DEFAULT (_PCNT_INPUT_S0PRSSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSSEL_PRSCH0 (_PCNT_INPUT_S0PRSSEL_PRSCH0 << 0) /**< Shifted mode PRSCH0 for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSSEL_PRSCH1 (_PCNT_INPUT_S0PRSSEL_PRSCH1 << 0) /**< Shifted mode PRSCH1 for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSSEL_PRSCH2 (_PCNT_INPUT_S0PRSSEL_PRSCH2 << 0) /**< Shifted mode PRSCH2 for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSSEL_PRSCH3 (_PCNT_INPUT_S0PRSSEL_PRSCH3 << 0) /**< Shifted mode PRSCH3 for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSEN (0x1UL << 4) /**< S0IN PRS Enable */
-#define _PCNT_INPUT_S0PRSEN_SHIFT 4 /**< Shift value for PCNT_S0PRSEN */
-#define _PCNT_INPUT_S0PRSEN_MASK 0x10UL /**< Bit mask for PCNT_S0PRSEN */
-#define _PCNT_INPUT_S0PRSEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_INPUT */
-#define PCNT_INPUT_S0PRSEN_DEFAULT (_PCNT_INPUT_S0PRSEN_DEFAULT << 4) /**< Shifted mode DEFAULT for PCNT_INPUT */
-#define _PCNT_INPUT_S1PRSSEL_SHIFT 6 /**< Shift value for PCNT_S1PRSSEL */
-#define _PCNT_INPUT_S1PRSSEL_MASK 0xC0UL /**< Bit mask for PCNT_S1PRSSEL */
-#define _PCNT_INPUT_S1PRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_INPUT */
-#define _PCNT_INPUT_S1PRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for PCNT_INPUT */
-#define _PCNT_INPUT_S1PRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for PCNT_INPUT */
-#define _PCNT_INPUT_S1PRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for PCNT_INPUT */
-#define _PCNT_INPUT_S1PRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSSEL_DEFAULT (_PCNT_INPUT_S1PRSSEL_DEFAULT << 6) /**< Shifted mode DEFAULT for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSSEL_PRSCH0 (_PCNT_INPUT_S1PRSSEL_PRSCH0 << 6) /**< Shifted mode PRSCH0 for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSSEL_PRSCH1 (_PCNT_INPUT_S1PRSSEL_PRSCH1 << 6) /**< Shifted mode PRSCH1 for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSSEL_PRSCH2 (_PCNT_INPUT_S1PRSSEL_PRSCH2 << 6) /**< Shifted mode PRSCH2 for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSSEL_PRSCH3 (_PCNT_INPUT_S1PRSSEL_PRSCH3 << 6) /**< Shifted mode PRSCH3 for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSEN (0x1UL << 10) /**< S1IN PRS Enable */
-#define _PCNT_INPUT_S1PRSEN_SHIFT 10 /**< Shift value for PCNT_S1PRSEN */
-#define _PCNT_INPUT_S1PRSEN_MASK 0x400UL /**< Bit mask for PCNT_S1PRSEN */
-#define _PCNT_INPUT_S1PRSEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PCNT_INPUT */
-#define PCNT_INPUT_S1PRSEN_DEFAULT (_PCNT_INPUT_S1PRSEN_DEFAULT << 10) /**< Shifted mode DEFAULT for PCNT_INPUT */
-
-/** @} End of group EFM32ZG_PCNT */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs.h
deleted file mode 100644
index 493930d30c..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs.h
+++ /dev/null
@@ -1,264 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_PRS register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_PRS
- * @{
- * @brief EFM32ZG_PRS Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t SWPULSE; /**< Software Pulse Register */
- __IOM uint32_t SWLEVEL; /**< Software Level Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved registers */
- PRS_CH_TypeDef CH[4U]; /**< Channel registers */
-} PRS_TypeDef; /** PRS Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_PRS_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for PRS SWPULSE */
-#define _PRS_SWPULSE_RESETVALUE 0x00000000UL /**< Default value for PRS_SWPULSE */
-#define _PRS_SWPULSE_MASK 0x0000000FUL /**< Mask for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE (0x1UL << 0) /**< Channel 0 Pulse Generation */
-#define _PRS_SWPULSE_CH0PULSE_SHIFT 0 /**< Shift value for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_MASK 0x1UL /**< Bit mask for PRS_CH0PULSE */
-#define _PRS_SWPULSE_CH0PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH0PULSE_DEFAULT (_PRS_SWPULSE_CH0PULSE_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE (0x1UL << 1) /**< Channel 1 Pulse Generation */
-#define _PRS_SWPULSE_CH1PULSE_SHIFT 1 /**< Shift value for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_MASK 0x2UL /**< Bit mask for PRS_CH1PULSE */
-#define _PRS_SWPULSE_CH1PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH1PULSE_DEFAULT (_PRS_SWPULSE_CH1PULSE_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE (0x1UL << 2) /**< Channel 2 Pulse Generation */
-#define _PRS_SWPULSE_CH2PULSE_SHIFT 2 /**< Shift value for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_MASK 0x4UL /**< Bit mask for PRS_CH2PULSE */
-#define _PRS_SWPULSE_CH2PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH2PULSE_DEFAULT (_PRS_SWPULSE_CH2PULSE_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE (0x1UL << 3) /**< Channel 3 Pulse Generation */
-#define _PRS_SWPULSE_CH3PULSE_SHIFT 3 /**< Shift value for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_MASK 0x8UL /**< Bit mask for PRS_CH3PULSE */
-#define _PRS_SWPULSE_CH3PULSE_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWPULSE */
-#define PRS_SWPULSE_CH3PULSE_DEFAULT (_PRS_SWPULSE_CH3PULSE_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWPULSE */
-
-/* Bit fields for PRS SWLEVEL */
-#define _PRS_SWLEVEL_RESETVALUE 0x00000000UL /**< Default value for PRS_SWLEVEL */
-#define _PRS_SWLEVEL_MASK 0x0000000FUL /**< Mask for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL (0x1UL << 0) /**< Channel 0 Software Level */
-#define _PRS_SWLEVEL_CH0LEVEL_SHIFT 0 /**< Shift value for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_MASK 0x1UL /**< Bit mask for PRS_CH0LEVEL */
-#define _PRS_SWLEVEL_CH0LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH0LEVEL_DEFAULT (_PRS_SWLEVEL_CH0LEVEL_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL (0x1UL << 1) /**< Channel 1 Software Level */
-#define _PRS_SWLEVEL_CH1LEVEL_SHIFT 1 /**< Shift value for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_MASK 0x2UL /**< Bit mask for PRS_CH1LEVEL */
-#define _PRS_SWLEVEL_CH1LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH1LEVEL_DEFAULT (_PRS_SWLEVEL_CH1LEVEL_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL (0x1UL << 2) /**< Channel 2 Software Level */
-#define _PRS_SWLEVEL_CH2LEVEL_SHIFT 2 /**< Shift value for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_MASK 0x4UL /**< Bit mask for PRS_CH2LEVEL */
-#define _PRS_SWLEVEL_CH2LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH2LEVEL_DEFAULT (_PRS_SWLEVEL_CH2LEVEL_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL (0x1UL << 3) /**< Channel 3 Software Level */
-#define _PRS_SWLEVEL_CH3LEVEL_SHIFT 3 /**< Shift value for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_MASK 0x8UL /**< Bit mask for PRS_CH3LEVEL */
-#define _PRS_SWLEVEL_CH3LEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_SWLEVEL */
-#define PRS_SWLEVEL_CH3LEVEL_DEFAULT (_PRS_SWLEVEL_CH3LEVEL_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_SWLEVEL */
-
-/* Bit fields for PRS ROUTE */
-#define _PRS_ROUTE_RESETVALUE 0x00000000UL /**< Default value for PRS_ROUTE */
-#define _PRS_ROUTE_MASK 0x0000070FUL /**< Mask for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN (0x1UL << 0) /**< CH0 Pin Enable */
-#define _PRS_ROUTE_CH0PEN_SHIFT 0 /**< Shift value for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_MASK 0x1UL /**< Bit mask for PRS_CH0PEN */
-#define _PRS_ROUTE_CH0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH0PEN_DEFAULT (_PRS_ROUTE_CH0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN (0x1UL << 1) /**< CH1 Pin Enable */
-#define _PRS_ROUTE_CH1PEN_SHIFT 1 /**< Shift value for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_MASK 0x2UL /**< Bit mask for PRS_CH1PEN */
-#define _PRS_ROUTE_CH1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH1PEN_DEFAULT (_PRS_ROUTE_CH1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN (0x1UL << 2) /**< CH2 Pin Enable */
-#define _PRS_ROUTE_CH2PEN_SHIFT 2 /**< Shift value for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_MASK 0x4UL /**< Bit mask for PRS_CH2PEN */
-#define _PRS_ROUTE_CH2PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH2PEN_DEFAULT (_PRS_ROUTE_CH2PEN_DEFAULT << 2) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN (0x1UL << 3) /**< CH3 Pin Enable */
-#define _PRS_ROUTE_CH3PEN_SHIFT 3 /**< Shift value for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_MASK 0x8UL /**< Bit mask for PRS_CH3PEN */
-#define _PRS_ROUTE_CH3PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_CH3PEN_DEFAULT (_PRS_ROUTE_CH3PEN_DEFAULT << 3) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_SHIFT 8 /**< Shift value for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for PRS_LOCATION */
-#define _PRS_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for PRS_ROUTE */
-#define _PRS_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC0 (_PRS_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_DEFAULT (_PRS_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC1 (_PRS_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for PRS_ROUTE */
-#define PRS_ROUTE_LOCATION_LOC2 (_PRS_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for PRS_ROUTE */
-
-/* Bit fields for PRS CH_CTRL */
-#define _PRS_CH_CTRL_RESETVALUE 0x00000000UL /**< Default value for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_MASK 0x133F0007UL /**< Mask for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_SHIFT 0 /**< Shift value for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_MASK 0x7UL /**< Bit mask for PRS_SIGSEL */
-#define _PRS_CH_CTRL_SIGSEL_VCMPOUT 0x00000000UL /**< Mode VCMPOUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ACMP0OUT 0x00000000UL /**< Mode ACMP0OUT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ADC0SINGLE 0x00000000UL /**< Mode ADC0SINGLE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1IRTX 0x00000000UL /**< Mode USART1IRTX for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0UF 0x00000000UL /**< Mode TIMER0UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1UF 0x00000000UL /**< Mode TIMER1UF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCOF 0x00000000UL /**< Mode RTCOF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN0 0x00000000UL /**< Mode GPIOPIN0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN8 0x00000000UL /**< Mode GPIOPIN8 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_PCNT0TCC 0x00000000UL /**< Mode PCNT0TCC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_ADC0SCAN 0x00000001UL /**< Mode ADC0SCAN for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1TXC 0x00000001UL /**< Mode USART1TXC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0OF 0x00000001UL /**< Mode TIMER0OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1OF 0x00000001UL /**< Mode TIMER1OF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP0 0x00000001UL /**< Mode RTCCOMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN1 0x00000001UL /**< Mode GPIOPIN1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN9 0x00000001UL /**< Mode GPIOPIN9 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_USART1RXDATAV 0x00000002UL /**< Mode USART1RXDATAV for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC0 0x00000002UL /**< Mode TIMER0CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC0 0x00000002UL /**< Mode TIMER1CC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_RTCCOMP1 0x00000002UL /**< Mode RTCCOMP1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN2 0x00000002UL /**< Mode GPIOPIN2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN10 0x00000002UL /**< Mode GPIOPIN10 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC1 0x00000003UL /**< Mode TIMER0CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC1 0x00000003UL /**< Mode TIMER1CC1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN3 0x00000003UL /**< Mode GPIOPIN3 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN11 0x00000003UL /**< Mode GPIOPIN11 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER0CC2 0x00000004UL /**< Mode TIMER0CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_TIMER1CC2 0x00000004UL /**< Mode TIMER1CC2 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN4 0x00000004UL /**< Mode GPIOPIN4 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN12 0x00000004UL /**< Mode GPIOPIN12 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN5 0x00000005UL /**< Mode GPIOPIN5 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN13 0x00000005UL /**< Mode GPIOPIN13 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN6 0x00000006UL /**< Mode GPIOPIN6 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN14 0x00000006UL /**< Mode GPIOPIN14 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN7 0x00000007UL /**< Mode GPIOPIN7 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SIGSEL_GPIOPIN15 0x00000007UL /**< Mode GPIOPIN15 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_VCMPOUT (_PRS_CH_CTRL_SIGSEL_VCMPOUT << 0) /**< Shifted mode VCMPOUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ACMP0OUT (_PRS_CH_CTRL_SIGSEL_ACMP0OUT << 0) /**< Shifted mode ACMP0OUT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ADC0SINGLE (_PRS_CH_CTRL_SIGSEL_ADC0SINGLE << 0) /**< Shifted mode ADC0SINGLE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1IRTX (_PRS_CH_CTRL_SIGSEL_USART1IRTX << 0) /**< Shifted mode USART1IRTX for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0UF (_PRS_CH_CTRL_SIGSEL_TIMER0UF << 0) /**< Shifted mode TIMER0UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1UF (_PRS_CH_CTRL_SIGSEL_TIMER1UF << 0) /**< Shifted mode TIMER1UF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCOF (_PRS_CH_CTRL_SIGSEL_RTCOF << 0) /**< Shifted mode RTCOF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN0 (_PRS_CH_CTRL_SIGSEL_GPIOPIN0 << 0) /**< Shifted mode GPIOPIN0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN8 (_PRS_CH_CTRL_SIGSEL_GPIOPIN8 << 0) /**< Shifted mode GPIOPIN8 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_PCNT0TCC (_PRS_CH_CTRL_SIGSEL_PCNT0TCC << 0) /**< Shifted mode PCNT0TCC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_ADC0SCAN (_PRS_CH_CTRL_SIGSEL_ADC0SCAN << 0) /**< Shifted mode ADC0SCAN for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1TXC (_PRS_CH_CTRL_SIGSEL_USART1TXC << 0) /**< Shifted mode USART1TXC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0OF (_PRS_CH_CTRL_SIGSEL_TIMER0OF << 0) /**< Shifted mode TIMER0OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1OF (_PRS_CH_CTRL_SIGSEL_TIMER1OF << 0) /**< Shifted mode TIMER1OF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP0 (_PRS_CH_CTRL_SIGSEL_RTCCOMP0 << 0) /**< Shifted mode RTCCOMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN1 (_PRS_CH_CTRL_SIGSEL_GPIOPIN1 << 0) /**< Shifted mode GPIOPIN1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN9 (_PRS_CH_CTRL_SIGSEL_GPIOPIN9 << 0) /**< Shifted mode GPIOPIN9 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_USART1RXDATAV (_PRS_CH_CTRL_SIGSEL_USART1RXDATAV << 0) /**< Shifted mode USART1RXDATAV for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC0 (_PRS_CH_CTRL_SIGSEL_TIMER0CC0 << 0) /**< Shifted mode TIMER0CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC0 (_PRS_CH_CTRL_SIGSEL_TIMER1CC0 << 0) /**< Shifted mode TIMER1CC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_RTCCOMP1 (_PRS_CH_CTRL_SIGSEL_RTCCOMP1 << 0) /**< Shifted mode RTCCOMP1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN2 (_PRS_CH_CTRL_SIGSEL_GPIOPIN2 << 0) /**< Shifted mode GPIOPIN2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN10 (_PRS_CH_CTRL_SIGSEL_GPIOPIN10 << 0) /**< Shifted mode GPIOPIN10 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC1 (_PRS_CH_CTRL_SIGSEL_TIMER0CC1 << 0) /**< Shifted mode TIMER0CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC1 (_PRS_CH_CTRL_SIGSEL_TIMER1CC1 << 0) /**< Shifted mode TIMER1CC1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN3 (_PRS_CH_CTRL_SIGSEL_GPIOPIN3 << 0) /**< Shifted mode GPIOPIN3 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN11 (_PRS_CH_CTRL_SIGSEL_GPIOPIN11 << 0) /**< Shifted mode GPIOPIN11 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER0CC2 (_PRS_CH_CTRL_SIGSEL_TIMER0CC2 << 0) /**< Shifted mode TIMER0CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_TIMER1CC2 (_PRS_CH_CTRL_SIGSEL_TIMER1CC2 << 0) /**< Shifted mode TIMER1CC2 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN4 (_PRS_CH_CTRL_SIGSEL_GPIOPIN4 << 0) /**< Shifted mode GPIOPIN4 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN12 (_PRS_CH_CTRL_SIGSEL_GPIOPIN12 << 0) /**< Shifted mode GPIOPIN12 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN5 (_PRS_CH_CTRL_SIGSEL_GPIOPIN5 << 0) /**< Shifted mode GPIOPIN5 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN13 (_PRS_CH_CTRL_SIGSEL_GPIOPIN13 << 0) /**< Shifted mode GPIOPIN13 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN6 (_PRS_CH_CTRL_SIGSEL_GPIOPIN6 << 0) /**< Shifted mode GPIOPIN6 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN14 (_PRS_CH_CTRL_SIGSEL_GPIOPIN14 << 0) /**< Shifted mode GPIOPIN14 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN7 (_PRS_CH_CTRL_SIGSEL_GPIOPIN7 << 0) /**< Shifted mode GPIOPIN7 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SIGSEL_GPIOPIN15 (_PRS_CH_CTRL_SIGSEL_GPIOPIN15 << 0) /**< Shifted mode GPIOPIN15 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_SHIFT 16 /**< Shift value for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_MASK 0x3F0000UL /**< Bit mask for PRS_SOURCESEL */
-#define _PRS_CH_CTRL_SOURCESEL_NONE 0x00000000UL /**< Mode NONE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_VCMP 0x00000001UL /**< Mode VCMP for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_ACMP0 0x00000002UL /**< Mode ACMP0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_ADC0 0x00000008UL /**< Mode ADC0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_USART1 0x00000011UL /**< Mode USART1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER0 0x0000001CUL /**< Mode TIMER0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_TIMER1 0x0000001DUL /**< Mode TIMER1 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_RTC 0x00000028UL /**< Mode RTC for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOL 0x00000030UL /**< Mode GPIOL for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_GPIOH 0x00000031UL /**< Mode GPIOH for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_SOURCESEL_PCNT0 0x00000036UL /**< Mode PCNT0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_NONE (_PRS_CH_CTRL_SOURCESEL_NONE << 16) /**< Shifted mode NONE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_VCMP (_PRS_CH_CTRL_SOURCESEL_VCMP << 16) /**< Shifted mode VCMP for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_ACMP0 (_PRS_CH_CTRL_SOURCESEL_ACMP0 << 16) /**< Shifted mode ACMP0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_ADC0 (_PRS_CH_CTRL_SOURCESEL_ADC0 << 16) /**< Shifted mode ADC0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_USART1 (_PRS_CH_CTRL_SOURCESEL_USART1 << 16) /**< Shifted mode USART1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER0 (_PRS_CH_CTRL_SOURCESEL_TIMER0 << 16) /**< Shifted mode TIMER0 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_TIMER1 (_PRS_CH_CTRL_SOURCESEL_TIMER1 << 16) /**< Shifted mode TIMER1 for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_RTC (_PRS_CH_CTRL_SOURCESEL_RTC << 16) /**< Shifted mode RTC for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOL (_PRS_CH_CTRL_SOURCESEL_GPIOL << 16) /**< Shifted mode GPIOL for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_GPIOH (_PRS_CH_CTRL_SOURCESEL_GPIOH << 16) /**< Shifted mode GPIOH for PRS_CH_CTRL */
-#define PRS_CH_CTRL_SOURCESEL_PCNT0 (_PRS_CH_CTRL_SOURCESEL_PCNT0 << 16) /**< Shifted mode PCNT0 for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_SHIFT 24 /**< Shift value for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_MASK 0x3000000UL /**< Bit mask for PRS_EDSEL */
-#define _PRS_CH_CTRL_EDSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_OFF 0x00000000UL /**< Mode OFF for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_POSEDGE 0x00000001UL /**< Mode POSEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_NEGEDGE 0x00000002UL /**< Mode NEGEDGE for PRS_CH_CTRL */
-#define _PRS_CH_CTRL_EDSEL_BOTHEDGES 0x00000003UL /**< Mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_DEFAULT (_PRS_CH_CTRL_EDSEL_DEFAULT << 24) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_OFF (_PRS_CH_CTRL_EDSEL_OFF << 24) /**< Shifted mode OFF for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_POSEDGE (_PRS_CH_CTRL_EDSEL_POSEDGE << 24) /**< Shifted mode POSEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_NEGEDGE (_PRS_CH_CTRL_EDSEL_NEGEDGE << 24) /**< Shifted mode NEGEDGE for PRS_CH_CTRL */
-#define PRS_CH_CTRL_EDSEL_BOTHEDGES (_PRS_CH_CTRL_EDSEL_BOTHEDGES << 24) /**< Shifted mode BOTHEDGES for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC (0x1UL << 28) /**< Asynchronous reflex */
-#define _PRS_CH_CTRL_ASYNC_SHIFT 28 /**< Shift value for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_MASK 0x10000000UL /**< Bit mask for PRS_ASYNC */
-#define _PRS_CH_CTRL_ASYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for PRS_CH_CTRL */
-#define PRS_CH_CTRL_ASYNC_DEFAULT (_PRS_CH_CTRL_ASYNC_DEFAULT << 28) /**< Shifted mode DEFAULT for PRS_CH_CTRL */
-
-/** @} End of group EFM32ZG_PRS */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs_ch.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs_ch.h
deleted file mode 100644
index 9dfed1682b..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs_ch.h
+++ /dev/null
@@ -1,48 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_PRS_CH register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @brief PRS_CH EFM32ZG PRS CH
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Channel Control Register */
-} PRS_CH_TypeDef;
-
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs_signals.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs_signals.h
deleted file mode 100644
index 5e11c6b880..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_prs_signals.h
+++ /dev/null
@@ -1,85 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_PRS_SIGNALS register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @addtogroup EFM32ZG_PRS_Signals
- * @{
- * @brief PRS Signal names
- ******************************************************************************/
-#define PRS_VCMP_OUT ((1 << 16) + 0) /**< PRS Voltage comparator output */
-#define PRS_ACMP0_OUT ((2 << 16) + 0) /**< PRS Analog comparator output */
-#define PRS_ADC0_SINGLE ((8 << 16) + 0) /**< PRS ADC single conversion done */
-#define PRS_ADC0_SCAN ((8 << 16) + 1) /**< PRS ADC scan conversion done */
-#define PRS_USART1_IRTX ((17 << 16) + 0) /**< PRS USART 1 IRDA out */
-#define PRS_USART1_TXC ((17 << 16) + 1) /**< PRS USART 1 TX complete */
-#define PRS_USART1_RXDATAV ((17 << 16) + 2) /**< PRS USART 1 RX Data Valid */
-#define PRS_TIMER0_UF ((28 << 16) + 0) /**< PRS Timer 0 Underflow */
-#define PRS_TIMER0_OF ((28 << 16) + 1) /**< PRS Timer 0 Overflow */
-#define PRS_TIMER0_CC0 ((28 << 16) + 2) /**< PRS Timer 0 Compare/Capture 0 */
-#define PRS_TIMER0_CC1 ((28 << 16) + 3) /**< PRS Timer 0 Compare/Capture 1 */
-#define PRS_TIMER0_CC2 ((28 << 16) + 4) /**< PRS Timer 0 Compare/Capture 2 */
-#define PRS_TIMER1_UF ((29 << 16) + 0) /**< PRS Timer 1 Underflow */
-#define PRS_TIMER1_OF ((29 << 16) + 1) /**< PRS Timer 1 Overflow */
-#define PRS_TIMER1_CC0 ((29 << 16) + 2) /**< PRS Timer 1 Compare/Capture 0 */
-#define PRS_TIMER1_CC1 ((29 << 16) + 3) /**< PRS Timer 1 Compare/Capture 1 */
-#define PRS_TIMER1_CC2 ((29 << 16) + 4) /**< PRS Timer 1 Compare/Capture 2 */
-#define PRS_RTC_OF ((40 << 16) + 0) /**< PRS RTC Overflow */
-#define PRS_RTC_COMP0 ((40 << 16) + 1) /**< PRS RTC Compare 0 */
-#define PRS_RTC_COMP1 ((40 << 16) + 2) /**< PRS RTC Compare 1 */
-#define PRS_GPIO_PIN0 ((48 << 16) + 0) /**< PRS GPIO pin 0 */
-#define PRS_GPIO_PIN1 ((48 << 16) + 1) /**< PRS GPIO pin 1 */
-#define PRS_GPIO_PIN2 ((48 << 16) + 2) /**< PRS GPIO pin 2 */
-#define PRS_GPIO_PIN3 ((48 << 16) + 3) /**< PRS GPIO pin 3 */
-#define PRS_GPIO_PIN4 ((48 << 16) + 4) /**< PRS GPIO pin 4 */
-#define PRS_GPIO_PIN5 ((48 << 16) + 5) /**< PRS GPIO pin 5 */
-#define PRS_GPIO_PIN6 ((48 << 16) + 6) /**< PRS GPIO pin 6 */
-#define PRS_GPIO_PIN7 ((48 << 16) + 7) /**< PRS GPIO pin 7 */
-#define PRS_GPIO_PIN8 ((49 << 16) + 0) /**< PRS GPIO pin 8 */
-#define PRS_GPIO_PIN9 ((49 << 16) + 1) /**< PRS GPIO pin 9 */
-#define PRS_GPIO_PIN10 ((49 << 16) + 2) /**< PRS GPIO pin 10 */
-#define PRS_GPIO_PIN11 ((49 << 16) + 3) /**< PRS GPIO pin 11 */
-#define PRS_GPIO_PIN12 ((49 << 16) + 4) /**< PRS GPIO pin 12 */
-#define PRS_GPIO_PIN13 ((49 << 16) + 5) /**< PRS GPIO pin 13 */
-#define PRS_GPIO_PIN14 ((49 << 16) + 6) /**< PRS GPIO pin 14 */
-#define PRS_GPIO_PIN15 ((49 << 16) + 7) /**< PRS GPIO pin 15 */
-#define PRS_PCNT0_TCC ((54 << 16) + 0) /**< PRS Triggered compare match */
-
-/** @} End of group EFM32ZG_PRS */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_rmu.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_rmu.h
deleted file mode 100644
index d298260ba0..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_rmu.h
+++ /dev/null
@@ -1,135 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_RMU register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_RMU
- * @{
- * @brief EFM32ZG_RMU Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IM uint32_t RSTCAUSE; /**< Reset Cause Register */
- __OM uint32_t CMD; /**< Command Register */
-} RMU_TypeDef; /** RMU Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_RMU_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for RMU CTRL */
-#define _RMU_CTRL_RESETVALUE 0x00000000UL /**< Default value for RMU_CTRL */
-#define _RMU_CTRL_MASK 0x00000001UL /**< Mask for RMU_CTRL */
-#define RMU_CTRL_LOCKUPRDIS (0x1UL << 0) /**< Lockup Reset Disable */
-#define _RMU_CTRL_LOCKUPRDIS_SHIFT 0 /**< Shift value for RMU_LOCKUPRDIS */
-#define _RMU_CTRL_LOCKUPRDIS_MASK 0x1UL /**< Bit mask for RMU_LOCKUPRDIS */
-#define _RMU_CTRL_LOCKUPRDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_CTRL */
-#define RMU_CTRL_LOCKUPRDIS_DEFAULT (_RMU_CTRL_LOCKUPRDIS_DEFAULT << 0) /**< Shifted mode DEFAULT for RMU_CTRL */
-
-/* Bit fields for RMU RSTCAUSE */
-#define _RMU_RSTCAUSE_RESETVALUE 0x00000000UL /**< Default value for RMU_RSTCAUSE */
-#define _RMU_RSTCAUSE_MASK 0x000007FFUL /**< Mask for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_PORST (0x1UL << 0) /**< Power On Reset */
-#define _RMU_RSTCAUSE_PORST_SHIFT 0 /**< Shift value for RMU_PORST */
-#define _RMU_RSTCAUSE_PORST_MASK 0x1UL /**< Bit mask for RMU_PORST */
-#define _RMU_RSTCAUSE_PORST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_PORST_DEFAULT (_RMU_RSTCAUSE_PORST_DEFAULT << 0) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODUNREGRST (0x1UL << 1) /**< Brown Out Detector Unregulated Domain Reset */
-#define _RMU_RSTCAUSE_BODUNREGRST_SHIFT 1 /**< Shift value for RMU_BODUNREGRST */
-#define _RMU_RSTCAUSE_BODUNREGRST_MASK 0x2UL /**< Bit mask for RMU_BODUNREGRST */
-#define _RMU_RSTCAUSE_BODUNREGRST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODUNREGRST_DEFAULT (_RMU_RSTCAUSE_BODUNREGRST_DEFAULT << 1) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODREGRST (0x1UL << 2) /**< Brown Out Detector Regulated Domain Reset */
-#define _RMU_RSTCAUSE_BODREGRST_SHIFT 2 /**< Shift value for RMU_BODREGRST */
-#define _RMU_RSTCAUSE_BODREGRST_MASK 0x4UL /**< Bit mask for RMU_BODREGRST */
-#define _RMU_RSTCAUSE_BODREGRST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODREGRST_DEFAULT (_RMU_RSTCAUSE_BODREGRST_DEFAULT << 2) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_EXTRST (0x1UL << 3) /**< External Pin Reset */
-#define _RMU_RSTCAUSE_EXTRST_SHIFT 3 /**< Shift value for RMU_EXTRST */
-#define _RMU_RSTCAUSE_EXTRST_MASK 0x8UL /**< Bit mask for RMU_EXTRST */
-#define _RMU_RSTCAUSE_EXTRST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_EXTRST_DEFAULT (_RMU_RSTCAUSE_EXTRST_DEFAULT << 3) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_WDOGRST (0x1UL << 4) /**< Watchdog Reset */
-#define _RMU_RSTCAUSE_WDOGRST_SHIFT 4 /**< Shift value for RMU_WDOGRST */
-#define _RMU_RSTCAUSE_WDOGRST_MASK 0x10UL /**< Bit mask for RMU_WDOGRST */
-#define _RMU_RSTCAUSE_WDOGRST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_WDOGRST_DEFAULT (_RMU_RSTCAUSE_WDOGRST_DEFAULT << 4) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_LOCKUPRST (0x1UL << 5) /**< LOCKUP Reset */
-#define _RMU_RSTCAUSE_LOCKUPRST_SHIFT 5 /**< Shift value for RMU_LOCKUPRST */
-#define _RMU_RSTCAUSE_LOCKUPRST_MASK 0x20UL /**< Bit mask for RMU_LOCKUPRST */
-#define _RMU_RSTCAUSE_LOCKUPRST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_LOCKUPRST_DEFAULT (_RMU_RSTCAUSE_LOCKUPRST_DEFAULT << 5) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_SYSREQRST (0x1UL << 6) /**< System Request Reset */
-#define _RMU_RSTCAUSE_SYSREQRST_SHIFT 6 /**< Shift value for RMU_SYSREQRST */
-#define _RMU_RSTCAUSE_SYSREQRST_MASK 0x40UL /**< Bit mask for RMU_SYSREQRST */
-#define _RMU_RSTCAUSE_SYSREQRST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_SYSREQRST_DEFAULT (_RMU_RSTCAUSE_SYSREQRST_DEFAULT << 6) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_EM4RST (0x1UL << 7) /**< EM4 Reset */
-#define _RMU_RSTCAUSE_EM4RST_SHIFT 7 /**< Shift value for RMU_EM4RST */
-#define _RMU_RSTCAUSE_EM4RST_MASK 0x80UL /**< Bit mask for RMU_EM4RST */
-#define _RMU_RSTCAUSE_EM4RST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_EM4RST_DEFAULT (_RMU_RSTCAUSE_EM4RST_DEFAULT << 7) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_EM4WURST (0x1UL << 8) /**< EM4 Wake-up Reset */
-#define _RMU_RSTCAUSE_EM4WURST_SHIFT 8 /**< Shift value for RMU_EM4WURST */
-#define _RMU_RSTCAUSE_EM4WURST_MASK 0x100UL /**< Bit mask for RMU_EM4WURST */
-#define _RMU_RSTCAUSE_EM4WURST_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_EM4WURST_DEFAULT (_RMU_RSTCAUSE_EM4WURST_DEFAULT << 8) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODAVDD0 (0x1UL << 9) /**< AVDD0 Bod Reset */
-#define _RMU_RSTCAUSE_BODAVDD0_SHIFT 9 /**< Shift value for RMU_BODAVDD0 */
-#define _RMU_RSTCAUSE_BODAVDD0_MASK 0x200UL /**< Bit mask for RMU_BODAVDD0 */
-#define _RMU_RSTCAUSE_BODAVDD0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODAVDD0_DEFAULT (_RMU_RSTCAUSE_BODAVDD0_DEFAULT << 9) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODAVDD1 (0x1UL << 10) /**< AVDD1 Bod Reset */
-#define _RMU_RSTCAUSE_BODAVDD1_SHIFT 10 /**< Shift value for RMU_BODAVDD1 */
-#define _RMU_RSTCAUSE_BODAVDD1_MASK 0x400UL /**< Bit mask for RMU_BODAVDD1 */
-#define _RMU_RSTCAUSE_BODAVDD1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_RSTCAUSE */
-#define RMU_RSTCAUSE_BODAVDD1_DEFAULT (_RMU_RSTCAUSE_BODAVDD1_DEFAULT << 10) /**< Shifted mode DEFAULT for RMU_RSTCAUSE */
-
-/* Bit fields for RMU CMD */
-#define _RMU_CMD_RESETVALUE 0x00000000UL /**< Default value for RMU_CMD */
-#define _RMU_CMD_MASK 0x00000001UL /**< Mask for RMU_CMD */
-#define RMU_CMD_RCCLR (0x1UL << 0) /**< Reset Cause Clear */
-#define _RMU_CMD_RCCLR_SHIFT 0 /**< Shift value for RMU_RCCLR */
-#define _RMU_CMD_RCCLR_MASK 0x1UL /**< Bit mask for RMU_RCCLR */
-#define _RMU_CMD_RCCLR_DEFAULT 0x00000000UL /**< Mode DEFAULT for RMU_CMD */
-#define RMU_CMD_RCCLR_DEFAULT (_RMU_CMD_RCCLR_DEFAULT << 0) /**< Shifted mode DEFAULT for RMU_CMD */
-
-/** @} End of group EFM32ZG_RMU */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_romtable.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_romtable.h
deleted file mode 100644
index aaab072efb..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_romtable.h
+++ /dev/null
@@ -1,75 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_ROMTABLE register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_ROMTABLE
- * @{
- * @brief Chip Information, Revision numbers
- ******************************************************************************/
-typedef struct {
- __IM uint32_t PID4; /**< JEP_106_BANK */
- __IM uint32_t PID5; /**< Unused */
- __IM uint32_t PID6; /**< Unused */
- __IM uint32_t PID7; /**< Unused */
- __IM uint32_t PID0; /**< Chip family LSB, chip major revision */
- __IM uint32_t PID1; /**< JEP_106_NO, Chip family MSB */
- __IM uint32_t PID2; /**< Chip minor rev MSB, JEP_106_PRESENT, JEP_106_NO */
- __IM uint32_t PID3; /**< Chip minor rev LSB */
- __IM uint32_t CID0; /**< Unused */
-} ROMTABLE_TypeDef; /** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_ROMTABLE_BitFields
- * @{
- ******************************************************************************/
-/* Bit fields for EFM32ZG_ROMTABLE */
-#define _ROMTABLE_PID0_FAMILYLSB_MASK 0x000000C0UL /**< Least Significant Bits [1:0] of CHIP FAMILY, mask */
-#define _ROMTABLE_PID0_FAMILYLSB_SHIFT 6 /**< Least Significant Bits [1:0] of CHIP FAMILY, shift */
-#define _ROMTABLE_PID0_REVMAJOR_MASK 0x0000003FUL /**< CHIP MAJOR Revison, mask */
-#define _ROMTABLE_PID0_REVMAJOR_SHIFT 0 /**< CHIP MAJOR Revison, shift */
-#define _ROMTABLE_PID1_FAMILYMSB_MASK 0x0000000FUL /**< Most Significant Bits [5:2] of CHIP FAMILY, mask */
-#define _ROMTABLE_PID1_FAMILYMSB_SHIFT 0 /**< Most Significant Bits [5:2] of CHIP FAMILY, shift */
-#define _ROMTABLE_PID2_REVMINORMSB_MASK 0x000000F0UL /**< Most Significant Bits [7:4] of CHIP MINOR revision, mask */
-#define _ROMTABLE_PID2_REVMINORMSB_SHIFT 4 /**< Most Significant Bits [7:4] of CHIP MINOR revision, mask */
-#define _ROMTABLE_PID3_REVMINORLSB_MASK 0x000000F0UL /**< Least Significant Bits [3:0] of CHIP MINOR revision, mask */
-#define _ROMTABLE_PID3_REVMINORLSB_SHIFT 4 /**< Least Significant Bits [3:0] of CHIP MINOR revision, shift */
-
-/** @} End of group EFM32ZG_ROMTABLE */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_rtc.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_rtc.h
deleted file mode 100644
index a422160d9c..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_rtc.h
+++ /dev/null
@@ -1,221 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_RTC register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_RTC
- * @{
- * @brief EFM32ZG_RTC Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CNT; /**< Counter Value Register */
- __IOM uint32_t COMP0; /**< Compare Value Register 0 */
- __IOM uint32_t COMP1; /**< Compare Value Register 1 */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
-
- __IOM uint32_t FREEZE; /**< Freeze Register */
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
-} RTC_TypeDef; /** RTC Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_RTC_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for RTC CTRL */
-#define _RTC_CTRL_RESETVALUE 0x00000000UL /**< Default value for RTC_CTRL */
-#define _RTC_CTRL_MASK 0x00000007UL /**< Mask for RTC_CTRL */
-#define RTC_CTRL_EN (0x1UL << 0) /**< RTC Enable */
-#define _RTC_CTRL_EN_SHIFT 0 /**< Shift value for RTC_EN */
-#define _RTC_CTRL_EN_MASK 0x1UL /**< Bit mask for RTC_EN */
-#define _RTC_CTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_CTRL */
-#define RTC_CTRL_EN_DEFAULT (_RTC_CTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_CTRL */
-#define RTC_CTRL_DEBUGRUN (0x1UL << 1) /**< Debug Mode Run Enable */
-#define _RTC_CTRL_DEBUGRUN_SHIFT 1 /**< Shift value for RTC_DEBUGRUN */
-#define _RTC_CTRL_DEBUGRUN_MASK 0x2UL /**< Bit mask for RTC_DEBUGRUN */
-#define _RTC_CTRL_DEBUGRUN_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_CTRL */
-#define RTC_CTRL_DEBUGRUN_DEFAULT (_RTC_CTRL_DEBUGRUN_DEFAULT << 1) /**< Shifted mode DEFAULT for RTC_CTRL */
-#define RTC_CTRL_COMP0TOP (0x1UL << 2) /**< Compare Channel 0 is Top Value */
-#define _RTC_CTRL_COMP0TOP_SHIFT 2 /**< Shift value for RTC_COMP0TOP */
-#define _RTC_CTRL_COMP0TOP_MASK 0x4UL /**< Bit mask for RTC_COMP0TOP */
-#define _RTC_CTRL_COMP0TOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_CTRL */
-#define _RTC_CTRL_COMP0TOP_DISABLE 0x00000000UL /**< Mode DISABLE for RTC_CTRL */
-#define _RTC_CTRL_COMP0TOP_ENABLE 0x00000001UL /**< Mode ENABLE for RTC_CTRL */
-#define RTC_CTRL_COMP0TOP_DEFAULT (_RTC_CTRL_COMP0TOP_DEFAULT << 2) /**< Shifted mode DEFAULT for RTC_CTRL */
-#define RTC_CTRL_COMP0TOP_DISABLE (_RTC_CTRL_COMP0TOP_DISABLE << 2) /**< Shifted mode DISABLE for RTC_CTRL */
-#define RTC_CTRL_COMP0TOP_ENABLE (_RTC_CTRL_COMP0TOP_ENABLE << 2) /**< Shifted mode ENABLE for RTC_CTRL */
-
-/* Bit fields for RTC CNT */
-#define _RTC_CNT_RESETVALUE 0x00000000UL /**< Default value for RTC_CNT */
-#define _RTC_CNT_MASK 0x00FFFFFFUL /**< Mask for RTC_CNT */
-#define _RTC_CNT_CNT_SHIFT 0 /**< Shift value for RTC_CNT */
-#define _RTC_CNT_CNT_MASK 0xFFFFFFUL /**< Bit mask for RTC_CNT */
-#define _RTC_CNT_CNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_CNT */
-#define RTC_CNT_CNT_DEFAULT (_RTC_CNT_CNT_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_CNT */
-
-/* Bit fields for RTC COMP0 */
-#define _RTC_COMP0_RESETVALUE 0x00000000UL /**< Default value for RTC_COMP0 */
-#define _RTC_COMP0_MASK 0x00FFFFFFUL /**< Mask for RTC_COMP0 */
-#define _RTC_COMP0_COMP0_SHIFT 0 /**< Shift value for RTC_COMP0 */
-#define _RTC_COMP0_COMP0_MASK 0xFFFFFFUL /**< Bit mask for RTC_COMP0 */
-#define _RTC_COMP0_COMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_COMP0 */
-#define RTC_COMP0_COMP0_DEFAULT (_RTC_COMP0_COMP0_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_COMP0 */
-
-/* Bit fields for RTC COMP1 */
-#define _RTC_COMP1_RESETVALUE 0x00000000UL /**< Default value for RTC_COMP1 */
-#define _RTC_COMP1_MASK 0x00FFFFFFUL /**< Mask for RTC_COMP1 */
-#define _RTC_COMP1_COMP1_SHIFT 0 /**< Shift value for RTC_COMP1 */
-#define _RTC_COMP1_COMP1_MASK 0xFFFFFFUL /**< Bit mask for RTC_COMP1 */
-#define _RTC_COMP1_COMP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_COMP1 */
-#define RTC_COMP1_COMP1_DEFAULT (_RTC_COMP1_COMP1_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_COMP1 */
-
-/* Bit fields for RTC IF */
-#define _RTC_IF_RESETVALUE 0x00000000UL /**< Default value for RTC_IF */
-#define _RTC_IF_MASK 0x00000007UL /**< Mask for RTC_IF */
-#define RTC_IF_OF (0x1UL << 0) /**< Overflow Interrupt Flag */
-#define _RTC_IF_OF_SHIFT 0 /**< Shift value for RTC_OF */
-#define _RTC_IF_OF_MASK 0x1UL /**< Bit mask for RTC_OF */
-#define _RTC_IF_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IF */
-#define RTC_IF_OF_DEFAULT (_RTC_IF_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_IF */
-#define RTC_IF_COMP0 (0x1UL << 1) /**< Compare Match 0 Interrupt Flag */
-#define _RTC_IF_COMP0_SHIFT 1 /**< Shift value for RTC_COMP0 */
-#define _RTC_IF_COMP0_MASK 0x2UL /**< Bit mask for RTC_COMP0 */
-#define _RTC_IF_COMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IF */
-#define RTC_IF_COMP0_DEFAULT (_RTC_IF_COMP0_DEFAULT << 1) /**< Shifted mode DEFAULT for RTC_IF */
-#define RTC_IF_COMP1 (0x1UL << 2) /**< Compare Match 1 Interrupt Flag */
-#define _RTC_IF_COMP1_SHIFT 2 /**< Shift value for RTC_COMP1 */
-#define _RTC_IF_COMP1_MASK 0x4UL /**< Bit mask for RTC_COMP1 */
-#define _RTC_IF_COMP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IF */
-#define RTC_IF_COMP1_DEFAULT (_RTC_IF_COMP1_DEFAULT << 2) /**< Shifted mode DEFAULT for RTC_IF */
-
-/* Bit fields for RTC IFS */
-#define _RTC_IFS_RESETVALUE 0x00000000UL /**< Default value for RTC_IFS */
-#define _RTC_IFS_MASK 0x00000007UL /**< Mask for RTC_IFS */
-#define RTC_IFS_OF (0x1UL << 0) /**< Set Overflow Interrupt Flag */
-#define _RTC_IFS_OF_SHIFT 0 /**< Shift value for RTC_OF */
-#define _RTC_IFS_OF_MASK 0x1UL /**< Bit mask for RTC_OF */
-#define _RTC_IFS_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IFS */
-#define RTC_IFS_OF_DEFAULT (_RTC_IFS_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_IFS */
-#define RTC_IFS_COMP0 (0x1UL << 1) /**< Set Compare match 0 Interrupt Flag */
-#define _RTC_IFS_COMP0_SHIFT 1 /**< Shift value for RTC_COMP0 */
-#define _RTC_IFS_COMP0_MASK 0x2UL /**< Bit mask for RTC_COMP0 */
-#define _RTC_IFS_COMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IFS */
-#define RTC_IFS_COMP0_DEFAULT (_RTC_IFS_COMP0_DEFAULT << 1) /**< Shifted mode DEFAULT for RTC_IFS */
-#define RTC_IFS_COMP1 (0x1UL << 2) /**< Set Compare match 1 Interrupt Flag */
-#define _RTC_IFS_COMP1_SHIFT 2 /**< Shift value for RTC_COMP1 */
-#define _RTC_IFS_COMP1_MASK 0x4UL /**< Bit mask for RTC_COMP1 */
-#define _RTC_IFS_COMP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IFS */
-#define RTC_IFS_COMP1_DEFAULT (_RTC_IFS_COMP1_DEFAULT << 2) /**< Shifted mode DEFAULT for RTC_IFS */
-
-/* Bit fields for RTC IFC */
-#define _RTC_IFC_RESETVALUE 0x00000000UL /**< Default value for RTC_IFC */
-#define _RTC_IFC_MASK 0x00000007UL /**< Mask for RTC_IFC */
-#define RTC_IFC_OF (0x1UL << 0) /**< Clear Overflow Interrupt Flag */
-#define _RTC_IFC_OF_SHIFT 0 /**< Shift value for RTC_OF */
-#define _RTC_IFC_OF_MASK 0x1UL /**< Bit mask for RTC_OF */
-#define _RTC_IFC_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IFC */
-#define RTC_IFC_OF_DEFAULT (_RTC_IFC_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_IFC */
-#define RTC_IFC_COMP0 (0x1UL << 1) /**< Clear Compare match 0 Interrupt Flag */
-#define _RTC_IFC_COMP0_SHIFT 1 /**< Shift value for RTC_COMP0 */
-#define _RTC_IFC_COMP0_MASK 0x2UL /**< Bit mask for RTC_COMP0 */
-#define _RTC_IFC_COMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IFC */
-#define RTC_IFC_COMP0_DEFAULT (_RTC_IFC_COMP0_DEFAULT << 1) /**< Shifted mode DEFAULT for RTC_IFC */
-#define RTC_IFC_COMP1 (0x1UL << 2) /**< Clear Compare match 1 Interrupt Flag */
-#define _RTC_IFC_COMP1_SHIFT 2 /**< Shift value for RTC_COMP1 */
-#define _RTC_IFC_COMP1_MASK 0x4UL /**< Bit mask for RTC_COMP1 */
-#define _RTC_IFC_COMP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IFC */
-#define RTC_IFC_COMP1_DEFAULT (_RTC_IFC_COMP1_DEFAULT << 2) /**< Shifted mode DEFAULT for RTC_IFC */
-
-/* Bit fields for RTC IEN */
-#define _RTC_IEN_RESETVALUE 0x00000000UL /**< Default value for RTC_IEN */
-#define _RTC_IEN_MASK 0x00000007UL /**< Mask for RTC_IEN */
-#define RTC_IEN_OF (0x1UL << 0) /**< Overflow Interrupt Enable */
-#define _RTC_IEN_OF_SHIFT 0 /**< Shift value for RTC_OF */
-#define _RTC_IEN_OF_MASK 0x1UL /**< Bit mask for RTC_OF */
-#define _RTC_IEN_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IEN */
-#define RTC_IEN_OF_DEFAULT (_RTC_IEN_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_IEN */
-#define RTC_IEN_COMP0 (0x1UL << 1) /**< Compare Match 0 Interrupt Enable */
-#define _RTC_IEN_COMP0_SHIFT 1 /**< Shift value for RTC_COMP0 */
-#define _RTC_IEN_COMP0_MASK 0x2UL /**< Bit mask for RTC_COMP0 */
-#define _RTC_IEN_COMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IEN */
-#define RTC_IEN_COMP0_DEFAULT (_RTC_IEN_COMP0_DEFAULT << 1) /**< Shifted mode DEFAULT for RTC_IEN */
-#define RTC_IEN_COMP1 (0x1UL << 2) /**< Compare Match 1 Interrupt Enable */
-#define _RTC_IEN_COMP1_SHIFT 2 /**< Shift value for RTC_COMP1 */
-#define _RTC_IEN_COMP1_MASK 0x4UL /**< Bit mask for RTC_COMP1 */
-#define _RTC_IEN_COMP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_IEN */
-#define RTC_IEN_COMP1_DEFAULT (_RTC_IEN_COMP1_DEFAULT << 2) /**< Shifted mode DEFAULT for RTC_IEN */
-
-/* Bit fields for RTC FREEZE */
-#define _RTC_FREEZE_RESETVALUE 0x00000000UL /**< Default value for RTC_FREEZE */
-#define _RTC_FREEZE_MASK 0x00000001UL /**< Mask for RTC_FREEZE */
-#define RTC_FREEZE_REGFREEZE (0x1UL << 0) /**< Register Update Freeze */
-#define _RTC_FREEZE_REGFREEZE_SHIFT 0 /**< Shift value for RTC_REGFREEZE */
-#define _RTC_FREEZE_REGFREEZE_MASK 0x1UL /**< Bit mask for RTC_REGFREEZE */
-#define _RTC_FREEZE_REGFREEZE_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_FREEZE */
-#define _RTC_FREEZE_REGFREEZE_UPDATE 0x00000000UL /**< Mode UPDATE for RTC_FREEZE */
-#define _RTC_FREEZE_REGFREEZE_FREEZE 0x00000001UL /**< Mode FREEZE for RTC_FREEZE */
-#define RTC_FREEZE_REGFREEZE_DEFAULT (_RTC_FREEZE_REGFREEZE_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_FREEZE */
-#define RTC_FREEZE_REGFREEZE_UPDATE (_RTC_FREEZE_REGFREEZE_UPDATE << 0) /**< Shifted mode UPDATE for RTC_FREEZE */
-#define RTC_FREEZE_REGFREEZE_FREEZE (_RTC_FREEZE_REGFREEZE_FREEZE << 0) /**< Shifted mode FREEZE for RTC_FREEZE */
-
-/* Bit fields for RTC SYNCBUSY */
-#define _RTC_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for RTC_SYNCBUSY */
-#define _RTC_SYNCBUSY_MASK 0x00000007UL /**< Mask for RTC_SYNCBUSY */
-#define RTC_SYNCBUSY_CTRL (0x1UL << 0) /**< CTRL Register Busy */
-#define _RTC_SYNCBUSY_CTRL_SHIFT 0 /**< Shift value for RTC_CTRL */
-#define _RTC_SYNCBUSY_CTRL_MASK 0x1UL /**< Bit mask for RTC_CTRL */
-#define _RTC_SYNCBUSY_CTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_SYNCBUSY */
-#define RTC_SYNCBUSY_CTRL_DEFAULT (_RTC_SYNCBUSY_CTRL_DEFAULT << 0) /**< Shifted mode DEFAULT for RTC_SYNCBUSY */
-#define RTC_SYNCBUSY_COMP0 (0x1UL << 1) /**< COMP0 Register Busy */
-#define _RTC_SYNCBUSY_COMP0_SHIFT 1 /**< Shift value for RTC_COMP0 */
-#define _RTC_SYNCBUSY_COMP0_MASK 0x2UL /**< Bit mask for RTC_COMP0 */
-#define _RTC_SYNCBUSY_COMP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_SYNCBUSY */
-#define RTC_SYNCBUSY_COMP0_DEFAULT (_RTC_SYNCBUSY_COMP0_DEFAULT << 1) /**< Shifted mode DEFAULT for RTC_SYNCBUSY */
-#define RTC_SYNCBUSY_COMP1 (0x1UL << 2) /**< COMP1 Register Busy */
-#define _RTC_SYNCBUSY_COMP1_SHIFT 2 /**< Shift value for RTC_COMP1 */
-#define _RTC_SYNCBUSY_COMP1_MASK 0x4UL /**< Bit mask for RTC_COMP1 */
-#define _RTC_SYNCBUSY_COMP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for RTC_SYNCBUSY */
-#define RTC_SYNCBUSY_COMP1_DEFAULT (_RTC_SYNCBUSY_COMP1_DEFAULT << 2) /**< Shifted mode DEFAULT for RTC_SYNCBUSY */
-
-/** @} End of group EFM32ZG_RTC */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_timer.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_timer.h
deleted file mode 100644
index f51e48bac4..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_timer.h
+++ /dev/null
@@ -1,667 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_TIMER register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_TIMER
- * @{
- * @brief EFM32ZG_TIMER Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t TOP; /**< Counter Top Value Register */
- __IOM uint32_t TOPB; /**< Counter Top Value Buffer Register */
- __IOM uint32_t CNT; /**< Counter Value Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
-
- uint32_t RESERVED0[1U]; /**< Reserved registers */
- TIMER_CC_TypeDef CC[3U]; /**< Compare/Capture Channel */
-} TIMER_TypeDef; /** TIMER Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_TIMER_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for TIMER CTRL */
-#define _TIMER_CTRL_RESETVALUE 0x00000000UL /**< Default value for TIMER_CTRL */
-#define _TIMER_CTRL_MASK 0x3F032FFBUL /**< Mask for TIMER_CTRL */
-#define _TIMER_CTRL_MODE_SHIFT 0 /**< Shift value for TIMER_MODE */
-#define _TIMER_CTRL_MODE_MASK 0x3UL /**< Bit mask for TIMER_MODE */
-#define _TIMER_CTRL_MODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_MODE_UP 0x00000000UL /**< Mode UP for TIMER_CTRL */
-#define _TIMER_CTRL_MODE_DOWN 0x00000001UL /**< Mode DOWN for TIMER_CTRL */
-#define _TIMER_CTRL_MODE_UPDOWN 0x00000002UL /**< Mode UPDOWN for TIMER_CTRL */
-#define _TIMER_CTRL_MODE_QDEC 0x00000003UL /**< Mode QDEC for TIMER_CTRL */
-#define TIMER_CTRL_MODE_DEFAULT (_TIMER_CTRL_MODE_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_MODE_UP (_TIMER_CTRL_MODE_UP << 0) /**< Shifted mode UP for TIMER_CTRL */
-#define TIMER_CTRL_MODE_DOWN (_TIMER_CTRL_MODE_DOWN << 0) /**< Shifted mode DOWN for TIMER_CTRL */
-#define TIMER_CTRL_MODE_UPDOWN (_TIMER_CTRL_MODE_UPDOWN << 0) /**< Shifted mode UPDOWN for TIMER_CTRL */
-#define TIMER_CTRL_MODE_QDEC (_TIMER_CTRL_MODE_QDEC << 0) /**< Shifted mode QDEC for TIMER_CTRL */
-#define TIMER_CTRL_SYNC (0x1UL << 3) /**< Timer Start/Stop/Reload Synchronization */
-#define _TIMER_CTRL_SYNC_SHIFT 3 /**< Shift value for TIMER_SYNC */
-#define _TIMER_CTRL_SYNC_MASK 0x8UL /**< Bit mask for TIMER_SYNC */
-#define _TIMER_CTRL_SYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_SYNC_DEFAULT (_TIMER_CTRL_SYNC_DEFAULT << 3) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_OSMEN (0x1UL << 4) /**< One-shot Mode Enable */
-#define _TIMER_CTRL_OSMEN_SHIFT 4 /**< Shift value for TIMER_OSMEN */
-#define _TIMER_CTRL_OSMEN_MASK 0x10UL /**< Bit mask for TIMER_OSMEN */
-#define _TIMER_CTRL_OSMEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_OSMEN_DEFAULT (_TIMER_CTRL_OSMEN_DEFAULT << 4) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_QDM (0x1UL << 5) /**< Quadrature Decoder Mode Selection */
-#define _TIMER_CTRL_QDM_SHIFT 5 /**< Shift value for TIMER_QDM */
-#define _TIMER_CTRL_QDM_MASK 0x20UL /**< Bit mask for TIMER_QDM */
-#define _TIMER_CTRL_QDM_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_QDM_X2 0x00000000UL /**< Mode X2 for TIMER_CTRL */
-#define _TIMER_CTRL_QDM_X4 0x00000001UL /**< Mode X4 for TIMER_CTRL */
-#define TIMER_CTRL_QDM_DEFAULT (_TIMER_CTRL_QDM_DEFAULT << 5) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_QDM_X2 (_TIMER_CTRL_QDM_X2 << 5) /**< Shifted mode X2 for TIMER_CTRL */
-#define TIMER_CTRL_QDM_X4 (_TIMER_CTRL_QDM_X4 << 5) /**< Shifted mode X4 for TIMER_CTRL */
-#define TIMER_CTRL_DEBUGRUN (0x1UL << 6) /**< Debug Mode Run Enable */
-#define _TIMER_CTRL_DEBUGRUN_SHIFT 6 /**< Shift value for TIMER_DEBUGRUN */
-#define _TIMER_CTRL_DEBUGRUN_MASK 0x40UL /**< Bit mask for TIMER_DEBUGRUN */
-#define _TIMER_CTRL_DEBUGRUN_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_DEBUGRUN_DEFAULT (_TIMER_CTRL_DEBUGRUN_DEFAULT << 6) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_DMACLRACT (0x1UL << 7) /**< DMA Request Clear on Active */
-#define _TIMER_CTRL_DMACLRACT_SHIFT 7 /**< Shift value for TIMER_DMACLRACT */
-#define _TIMER_CTRL_DMACLRACT_MASK 0x80UL /**< Bit mask for TIMER_DMACLRACT */
-#define _TIMER_CTRL_DMACLRACT_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_DMACLRACT_DEFAULT (_TIMER_CTRL_DMACLRACT_DEFAULT << 7) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_RISEA_SHIFT 8 /**< Shift value for TIMER_RISEA */
-#define _TIMER_CTRL_RISEA_MASK 0x300UL /**< Bit mask for TIMER_RISEA */
-#define _TIMER_CTRL_RISEA_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_RISEA_NONE 0x00000000UL /**< Mode NONE for TIMER_CTRL */
-#define _TIMER_CTRL_RISEA_START 0x00000001UL /**< Mode START for TIMER_CTRL */
-#define _TIMER_CTRL_RISEA_STOP 0x00000002UL /**< Mode STOP for TIMER_CTRL */
-#define _TIMER_CTRL_RISEA_RELOADSTART 0x00000003UL /**< Mode RELOADSTART for TIMER_CTRL */
-#define TIMER_CTRL_RISEA_DEFAULT (_TIMER_CTRL_RISEA_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_RISEA_NONE (_TIMER_CTRL_RISEA_NONE << 8) /**< Shifted mode NONE for TIMER_CTRL */
-#define TIMER_CTRL_RISEA_START (_TIMER_CTRL_RISEA_START << 8) /**< Shifted mode START for TIMER_CTRL */
-#define TIMER_CTRL_RISEA_STOP (_TIMER_CTRL_RISEA_STOP << 8) /**< Shifted mode STOP for TIMER_CTRL */
-#define TIMER_CTRL_RISEA_RELOADSTART (_TIMER_CTRL_RISEA_RELOADSTART << 8) /**< Shifted mode RELOADSTART for TIMER_CTRL */
-#define _TIMER_CTRL_FALLA_SHIFT 10 /**< Shift value for TIMER_FALLA */
-#define _TIMER_CTRL_FALLA_MASK 0xC00UL /**< Bit mask for TIMER_FALLA */
-#define _TIMER_CTRL_FALLA_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_FALLA_NONE 0x00000000UL /**< Mode NONE for TIMER_CTRL */
-#define _TIMER_CTRL_FALLA_START 0x00000001UL /**< Mode START for TIMER_CTRL */
-#define _TIMER_CTRL_FALLA_STOP 0x00000002UL /**< Mode STOP for TIMER_CTRL */
-#define _TIMER_CTRL_FALLA_RELOADSTART 0x00000003UL /**< Mode RELOADSTART for TIMER_CTRL */
-#define TIMER_CTRL_FALLA_DEFAULT (_TIMER_CTRL_FALLA_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_FALLA_NONE (_TIMER_CTRL_FALLA_NONE << 10) /**< Shifted mode NONE for TIMER_CTRL */
-#define TIMER_CTRL_FALLA_START (_TIMER_CTRL_FALLA_START << 10) /**< Shifted mode START for TIMER_CTRL */
-#define TIMER_CTRL_FALLA_STOP (_TIMER_CTRL_FALLA_STOP << 10) /**< Shifted mode STOP for TIMER_CTRL */
-#define TIMER_CTRL_FALLA_RELOADSTART (_TIMER_CTRL_FALLA_RELOADSTART << 10) /**< Shifted mode RELOADSTART for TIMER_CTRL */
-#define TIMER_CTRL_X2CNT (0x1UL << 13) /**< 2x Count Mode */
-#define _TIMER_CTRL_X2CNT_SHIFT 13 /**< Shift value for TIMER_X2CNT */
-#define _TIMER_CTRL_X2CNT_MASK 0x2000UL /**< Bit mask for TIMER_X2CNT */
-#define _TIMER_CTRL_X2CNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_X2CNT_DEFAULT (_TIMER_CTRL_X2CNT_DEFAULT << 13) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_CLKSEL_SHIFT 16 /**< Shift value for TIMER_CLKSEL */
-#define _TIMER_CTRL_CLKSEL_MASK 0x30000UL /**< Bit mask for TIMER_CLKSEL */
-#define _TIMER_CTRL_CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_CLKSEL_PRESCHFPERCLK 0x00000000UL /**< Mode PRESCHFPERCLK for TIMER_CTRL */
-#define _TIMER_CTRL_CLKSEL_CC1 0x00000001UL /**< Mode CC1 for TIMER_CTRL */
-#define _TIMER_CTRL_CLKSEL_TIMEROUF 0x00000002UL /**< Mode TIMEROUF for TIMER_CTRL */
-#define TIMER_CTRL_CLKSEL_DEFAULT (_TIMER_CTRL_CLKSEL_DEFAULT << 16) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_CLKSEL_PRESCHFPERCLK (_TIMER_CTRL_CLKSEL_PRESCHFPERCLK << 16) /**< Shifted mode PRESCHFPERCLK for TIMER_CTRL */
-#define TIMER_CTRL_CLKSEL_CC1 (_TIMER_CTRL_CLKSEL_CC1 << 16) /**< Shifted mode CC1 for TIMER_CTRL */
-#define TIMER_CTRL_CLKSEL_TIMEROUF (_TIMER_CTRL_CLKSEL_TIMEROUF << 16) /**< Shifted mode TIMEROUF for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_SHIFT 24 /**< Shift value for TIMER_PRESC */
-#define _TIMER_CTRL_PRESC_MASK 0xF000000UL /**< Bit mask for TIMER_PRESC */
-#define _TIMER_CTRL_PRESC_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV1 0x00000000UL /**< Mode DIV1 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV2 0x00000001UL /**< Mode DIV2 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV4 0x00000002UL /**< Mode DIV4 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV8 0x00000003UL /**< Mode DIV8 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV16 0x00000004UL /**< Mode DIV16 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV32 0x00000005UL /**< Mode DIV32 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV64 0x00000006UL /**< Mode DIV64 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV128 0x00000007UL /**< Mode DIV128 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV256 0x00000008UL /**< Mode DIV256 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV512 0x00000009UL /**< Mode DIV512 for TIMER_CTRL */
-#define _TIMER_CTRL_PRESC_DIV1024 0x0000000AUL /**< Mode DIV1024 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DEFAULT (_TIMER_CTRL_PRESC_DEFAULT << 24) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV1 (_TIMER_CTRL_PRESC_DIV1 << 24) /**< Shifted mode DIV1 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV2 (_TIMER_CTRL_PRESC_DIV2 << 24) /**< Shifted mode DIV2 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV4 (_TIMER_CTRL_PRESC_DIV4 << 24) /**< Shifted mode DIV4 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV8 (_TIMER_CTRL_PRESC_DIV8 << 24) /**< Shifted mode DIV8 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV16 (_TIMER_CTRL_PRESC_DIV16 << 24) /**< Shifted mode DIV16 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV32 (_TIMER_CTRL_PRESC_DIV32 << 24) /**< Shifted mode DIV32 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV64 (_TIMER_CTRL_PRESC_DIV64 << 24) /**< Shifted mode DIV64 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV128 (_TIMER_CTRL_PRESC_DIV128 << 24) /**< Shifted mode DIV128 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV256 (_TIMER_CTRL_PRESC_DIV256 << 24) /**< Shifted mode DIV256 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV512 (_TIMER_CTRL_PRESC_DIV512 << 24) /**< Shifted mode DIV512 for TIMER_CTRL */
-#define TIMER_CTRL_PRESC_DIV1024 (_TIMER_CTRL_PRESC_DIV1024 << 24) /**< Shifted mode DIV1024 for TIMER_CTRL */
-#define TIMER_CTRL_ATI (0x1UL << 28) /**< Always Track Inputs */
-#define _TIMER_CTRL_ATI_SHIFT 28 /**< Shift value for TIMER_ATI */
-#define _TIMER_CTRL_ATI_MASK 0x10000000UL /**< Bit mask for TIMER_ATI */
-#define _TIMER_CTRL_ATI_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_ATI_DEFAULT (_TIMER_CTRL_ATI_DEFAULT << 28) /**< Shifted mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_RSSCOIST (0x1UL << 29) /**< Reload-Start Sets Compare Output initial State */
-#define _TIMER_CTRL_RSSCOIST_SHIFT 29 /**< Shift value for TIMER_RSSCOIST */
-#define _TIMER_CTRL_RSSCOIST_MASK 0x20000000UL /**< Bit mask for TIMER_RSSCOIST */
-#define _TIMER_CTRL_RSSCOIST_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CTRL */
-#define TIMER_CTRL_RSSCOIST_DEFAULT (_TIMER_CTRL_RSSCOIST_DEFAULT << 29) /**< Shifted mode DEFAULT for TIMER_CTRL */
-
-/* Bit fields for TIMER CMD */
-#define _TIMER_CMD_RESETVALUE 0x00000000UL /**< Default value for TIMER_CMD */
-#define _TIMER_CMD_MASK 0x00000003UL /**< Mask for TIMER_CMD */
-#define TIMER_CMD_START (0x1UL << 0) /**< Start Timer */
-#define _TIMER_CMD_START_SHIFT 0 /**< Shift value for TIMER_START */
-#define _TIMER_CMD_START_MASK 0x1UL /**< Bit mask for TIMER_START */
-#define _TIMER_CMD_START_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CMD */
-#define TIMER_CMD_START_DEFAULT (_TIMER_CMD_START_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CMD */
-#define TIMER_CMD_STOP (0x1UL << 1) /**< Stop Timer */
-#define _TIMER_CMD_STOP_SHIFT 1 /**< Shift value for TIMER_STOP */
-#define _TIMER_CMD_STOP_MASK 0x2UL /**< Bit mask for TIMER_STOP */
-#define _TIMER_CMD_STOP_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CMD */
-#define TIMER_CMD_STOP_DEFAULT (_TIMER_CMD_STOP_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_CMD */
-
-/* Bit fields for TIMER STATUS */
-#define _TIMER_STATUS_RESETVALUE 0x00000000UL /**< Default value for TIMER_STATUS */
-#define _TIMER_STATUS_MASK 0x07070707UL /**< Mask for TIMER_STATUS */
-#define TIMER_STATUS_RUNNING (0x1UL << 0) /**< Running */
-#define _TIMER_STATUS_RUNNING_SHIFT 0 /**< Shift value for TIMER_RUNNING */
-#define _TIMER_STATUS_RUNNING_MASK 0x1UL /**< Bit mask for TIMER_RUNNING */
-#define _TIMER_STATUS_RUNNING_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_RUNNING_DEFAULT (_TIMER_STATUS_RUNNING_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_DIR (0x1UL << 1) /**< Direction */
-#define _TIMER_STATUS_DIR_SHIFT 1 /**< Shift value for TIMER_DIR */
-#define _TIMER_STATUS_DIR_MASK 0x2UL /**< Bit mask for TIMER_DIR */
-#define _TIMER_STATUS_DIR_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define _TIMER_STATUS_DIR_UP 0x00000000UL /**< Mode UP for TIMER_STATUS */
-#define _TIMER_STATUS_DIR_DOWN 0x00000001UL /**< Mode DOWN for TIMER_STATUS */
-#define TIMER_STATUS_DIR_DEFAULT (_TIMER_STATUS_DIR_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_DIR_UP (_TIMER_STATUS_DIR_UP << 1) /**< Shifted mode UP for TIMER_STATUS */
-#define TIMER_STATUS_DIR_DOWN (_TIMER_STATUS_DIR_DOWN << 1) /**< Shifted mode DOWN for TIMER_STATUS */
-#define TIMER_STATUS_TOPBV (0x1UL << 2) /**< TOPB Valid */
-#define _TIMER_STATUS_TOPBV_SHIFT 2 /**< Shift value for TIMER_TOPBV */
-#define _TIMER_STATUS_TOPBV_MASK 0x4UL /**< Bit mask for TIMER_TOPBV */
-#define _TIMER_STATUS_TOPBV_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_TOPBV_DEFAULT (_TIMER_STATUS_TOPBV_DEFAULT << 2) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCVBV0 (0x1UL << 8) /**< CC0 CCVB Valid */
-#define _TIMER_STATUS_CCVBV0_SHIFT 8 /**< Shift value for TIMER_CCVBV0 */
-#define _TIMER_STATUS_CCVBV0_MASK 0x100UL /**< Bit mask for TIMER_CCVBV0 */
-#define _TIMER_STATUS_CCVBV0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCVBV0_DEFAULT (_TIMER_STATUS_CCVBV0_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCVBV1 (0x1UL << 9) /**< CC1 CCVB Valid */
-#define _TIMER_STATUS_CCVBV1_SHIFT 9 /**< Shift value for TIMER_CCVBV1 */
-#define _TIMER_STATUS_CCVBV1_MASK 0x200UL /**< Bit mask for TIMER_CCVBV1 */
-#define _TIMER_STATUS_CCVBV1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCVBV1_DEFAULT (_TIMER_STATUS_CCVBV1_DEFAULT << 9) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCVBV2 (0x1UL << 10) /**< CC2 CCVB Valid */
-#define _TIMER_STATUS_CCVBV2_SHIFT 10 /**< Shift value for TIMER_CCVBV2 */
-#define _TIMER_STATUS_CCVBV2_MASK 0x400UL /**< Bit mask for TIMER_CCVBV2 */
-#define _TIMER_STATUS_CCVBV2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCVBV2_DEFAULT (_TIMER_STATUS_CCVBV2_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_ICV0 (0x1UL << 16) /**< CC0 Input Capture Valid */
-#define _TIMER_STATUS_ICV0_SHIFT 16 /**< Shift value for TIMER_ICV0 */
-#define _TIMER_STATUS_ICV0_MASK 0x10000UL /**< Bit mask for TIMER_ICV0 */
-#define _TIMER_STATUS_ICV0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_ICV0_DEFAULT (_TIMER_STATUS_ICV0_DEFAULT << 16) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_ICV1 (0x1UL << 17) /**< CC1 Input Capture Valid */
-#define _TIMER_STATUS_ICV1_SHIFT 17 /**< Shift value for TIMER_ICV1 */
-#define _TIMER_STATUS_ICV1_MASK 0x20000UL /**< Bit mask for TIMER_ICV1 */
-#define _TIMER_STATUS_ICV1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_ICV1_DEFAULT (_TIMER_STATUS_ICV1_DEFAULT << 17) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_ICV2 (0x1UL << 18) /**< CC2 Input Capture Valid */
-#define _TIMER_STATUS_ICV2_SHIFT 18 /**< Shift value for TIMER_ICV2 */
-#define _TIMER_STATUS_ICV2_MASK 0x40000UL /**< Bit mask for TIMER_ICV2 */
-#define _TIMER_STATUS_ICV2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_ICV2_DEFAULT (_TIMER_STATUS_ICV2_DEFAULT << 18) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL0 (0x1UL << 24) /**< CC0 Polarity */
-#define _TIMER_STATUS_CCPOL0_SHIFT 24 /**< Shift value for TIMER_CCPOL0 */
-#define _TIMER_STATUS_CCPOL0_MASK 0x1000000UL /**< Bit mask for TIMER_CCPOL0 */
-#define _TIMER_STATUS_CCPOL0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define _TIMER_STATUS_CCPOL0_LOWRISE 0x00000000UL /**< Mode LOWRISE for TIMER_STATUS */
-#define _TIMER_STATUS_CCPOL0_HIGHFALL 0x00000001UL /**< Mode HIGHFALL for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL0_DEFAULT (_TIMER_STATUS_CCPOL0_DEFAULT << 24) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL0_LOWRISE (_TIMER_STATUS_CCPOL0_LOWRISE << 24) /**< Shifted mode LOWRISE for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL0_HIGHFALL (_TIMER_STATUS_CCPOL0_HIGHFALL << 24) /**< Shifted mode HIGHFALL for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL1 (0x1UL << 25) /**< CC1 Polarity */
-#define _TIMER_STATUS_CCPOL1_SHIFT 25 /**< Shift value for TIMER_CCPOL1 */
-#define _TIMER_STATUS_CCPOL1_MASK 0x2000000UL /**< Bit mask for TIMER_CCPOL1 */
-#define _TIMER_STATUS_CCPOL1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define _TIMER_STATUS_CCPOL1_LOWRISE 0x00000000UL /**< Mode LOWRISE for TIMER_STATUS */
-#define _TIMER_STATUS_CCPOL1_HIGHFALL 0x00000001UL /**< Mode HIGHFALL for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL1_DEFAULT (_TIMER_STATUS_CCPOL1_DEFAULT << 25) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL1_LOWRISE (_TIMER_STATUS_CCPOL1_LOWRISE << 25) /**< Shifted mode LOWRISE for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL1_HIGHFALL (_TIMER_STATUS_CCPOL1_HIGHFALL << 25) /**< Shifted mode HIGHFALL for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL2 (0x1UL << 26) /**< CC2 Polarity */
-#define _TIMER_STATUS_CCPOL2_SHIFT 26 /**< Shift value for TIMER_CCPOL2 */
-#define _TIMER_STATUS_CCPOL2_MASK 0x4000000UL /**< Bit mask for TIMER_CCPOL2 */
-#define _TIMER_STATUS_CCPOL2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_STATUS */
-#define _TIMER_STATUS_CCPOL2_LOWRISE 0x00000000UL /**< Mode LOWRISE for TIMER_STATUS */
-#define _TIMER_STATUS_CCPOL2_HIGHFALL 0x00000001UL /**< Mode HIGHFALL for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL2_DEFAULT (_TIMER_STATUS_CCPOL2_DEFAULT << 26) /**< Shifted mode DEFAULT for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL2_LOWRISE (_TIMER_STATUS_CCPOL2_LOWRISE << 26) /**< Shifted mode LOWRISE for TIMER_STATUS */
-#define TIMER_STATUS_CCPOL2_HIGHFALL (_TIMER_STATUS_CCPOL2_HIGHFALL << 26) /**< Shifted mode HIGHFALL for TIMER_STATUS */
-
-/* Bit fields for TIMER IEN */
-#define _TIMER_IEN_RESETVALUE 0x00000000UL /**< Default value for TIMER_IEN */
-#define _TIMER_IEN_MASK 0x00000773UL /**< Mask for TIMER_IEN */
-#define TIMER_IEN_OF (0x1UL << 0) /**< Overflow Interrupt Enable */
-#define _TIMER_IEN_OF_SHIFT 0 /**< Shift value for TIMER_OF */
-#define _TIMER_IEN_OF_MASK 0x1UL /**< Bit mask for TIMER_OF */
-#define _TIMER_IEN_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_OF_DEFAULT (_TIMER_IEN_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_UF (0x1UL << 1) /**< Underflow Interrupt Enable */
-#define _TIMER_IEN_UF_SHIFT 1 /**< Shift value for TIMER_UF */
-#define _TIMER_IEN_UF_MASK 0x2UL /**< Bit mask for TIMER_UF */
-#define _TIMER_IEN_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_UF_DEFAULT (_TIMER_IEN_UF_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_CC0 (0x1UL << 4) /**< CC Channel 0 Interrupt Enable */
-#define _TIMER_IEN_CC0_SHIFT 4 /**< Shift value for TIMER_CC0 */
-#define _TIMER_IEN_CC0_MASK 0x10UL /**< Bit mask for TIMER_CC0 */
-#define _TIMER_IEN_CC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_CC0_DEFAULT (_TIMER_IEN_CC0_DEFAULT << 4) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_CC1 (0x1UL << 5) /**< CC Channel 1 Interrupt Enable */
-#define _TIMER_IEN_CC1_SHIFT 5 /**< Shift value for TIMER_CC1 */
-#define _TIMER_IEN_CC1_MASK 0x20UL /**< Bit mask for TIMER_CC1 */
-#define _TIMER_IEN_CC1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_CC1_DEFAULT (_TIMER_IEN_CC1_DEFAULT << 5) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_CC2 (0x1UL << 6) /**< CC Channel 2 Interrupt Enable */
-#define _TIMER_IEN_CC2_SHIFT 6 /**< Shift value for TIMER_CC2 */
-#define _TIMER_IEN_CC2_MASK 0x40UL /**< Bit mask for TIMER_CC2 */
-#define _TIMER_IEN_CC2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_CC2_DEFAULT (_TIMER_IEN_CC2_DEFAULT << 6) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_ICBOF0 (0x1UL << 8) /**< CC Channel 0 Input Capture Buffer Overflow Interrupt Enable */
-#define _TIMER_IEN_ICBOF0_SHIFT 8 /**< Shift value for TIMER_ICBOF0 */
-#define _TIMER_IEN_ICBOF0_MASK 0x100UL /**< Bit mask for TIMER_ICBOF0 */
-#define _TIMER_IEN_ICBOF0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_ICBOF0_DEFAULT (_TIMER_IEN_ICBOF0_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_ICBOF1 (0x1UL << 9) /**< CC Channel 1 Input Capture Buffer Overflow Interrupt Enable */
-#define _TIMER_IEN_ICBOF1_SHIFT 9 /**< Shift value for TIMER_ICBOF1 */
-#define _TIMER_IEN_ICBOF1_MASK 0x200UL /**< Bit mask for TIMER_ICBOF1 */
-#define _TIMER_IEN_ICBOF1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_ICBOF1_DEFAULT (_TIMER_IEN_ICBOF1_DEFAULT << 9) /**< Shifted mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_ICBOF2 (0x1UL << 10) /**< CC Channel 2 Input Capture Buffer Overflow Interrupt Enable */
-#define _TIMER_IEN_ICBOF2_SHIFT 10 /**< Shift value for TIMER_ICBOF2 */
-#define _TIMER_IEN_ICBOF2_MASK 0x400UL /**< Bit mask for TIMER_ICBOF2 */
-#define _TIMER_IEN_ICBOF2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IEN */
-#define TIMER_IEN_ICBOF2_DEFAULT (_TIMER_IEN_ICBOF2_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_IEN */
-
-/* Bit fields for TIMER IF */
-#define _TIMER_IF_RESETVALUE 0x00000000UL /**< Default value for TIMER_IF */
-#define _TIMER_IF_MASK 0x00000773UL /**< Mask for TIMER_IF */
-#define TIMER_IF_OF (0x1UL << 0) /**< Overflow Interrupt Flag */
-#define _TIMER_IF_OF_SHIFT 0 /**< Shift value for TIMER_OF */
-#define _TIMER_IF_OF_MASK 0x1UL /**< Bit mask for TIMER_OF */
-#define _TIMER_IF_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_OF_DEFAULT (_TIMER_IF_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_UF (0x1UL << 1) /**< Underflow Interrupt Flag */
-#define _TIMER_IF_UF_SHIFT 1 /**< Shift value for TIMER_UF */
-#define _TIMER_IF_UF_MASK 0x2UL /**< Bit mask for TIMER_UF */
-#define _TIMER_IF_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_UF_DEFAULT (_TIMER_IF_UF_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_CC0 (0x1UL << 4) /**< CC Channel 0 Interrupt Flag */
-#define _TIMER_IF_CC0_SHIFT 4 /**< Shift value for TIMER_CC0 */
-#define _TIMER_IF_CC0_MASK 0x10UL /**< Bit mask for TIMER_CC0 */
-#define _TIMER_IF_CC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_CC0_DEFAULT (_TIMER_IF_CC0_DEFAULT << 4) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_CC1 (0x1UL << 5) /**< CC Channel 1 Interrupt Flag */
-#define _TIMER_IF_CC1_SHIFT 5 /**< Shift value for TIMER_CC1 */
-#define _TIMER_IF_CC1_MASK 0x20UL /**< Bit mask for TIMER_CC1 */
-#define _TIMER_IF_CC1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_CC1_DEFAULT (_TIMER_IF_CC1_DEFAULT << 5) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_CC2 (0x1UL << 6) /**< CC Channel 2 Interrupt Flag */
-#define _TIMER_IF_CC2_SHIFT 6 /**< Shift value for TIMER_CC2 */
-#define _TIMER_IF_CC2_MASK 0x40UL /**< Bit mask for TIMER_CC2 */
-#define _TIMER_IF_CC2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_CC2_DEFAULT (_TIMER_IF_CC2_DEFAULT << 6) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_ICBOF0 (0x1UL << 8) /**< CC Channel 0 Input Capture Buffer Overflow Interrupt Flag */
-#define _TIMER_IF_ICBOF0_SHIFT 8 /**< Shift value for TIMER_ICBOF0 */
-#define _TIMER_IF_ICBOF0_MASK 0x100UL /**< Bit mask for TIMER_ICBOF0 */
-#define _TIMER_IF_ICBOF0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_ICBOF0_DEFAULT (_TIMER_IF_ICBOF0_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_ICBOF1 (0x1UL << 9) /**< CC Channel 1 Input Capture Buffer Overflow Interrupt Flag */
-#define _TIMER_IF_ICBOF1_SHIFT 9 /**< Shift value for TIMER_ICBOF1 */
-#define _TIMER_IF_ICBOF1_MASK 0x200UL /**< Bit mask for TIMER_ICBOF1 */
-#define _TIMER_IF_ICBOF1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_ICBOF1_DEFAULT (_TIMER_IF_ICBOF1_DEFAULT << 9) /**< Shifted mode DEFAULT for TIMER_IF */
-#define TIMER_IF_ICBOF2 (0x1UL << 10) /**< CC Channel 2 Input Capture Buffer Overflow Interrupt Flag */
-#define _TIMER_IF_ICBOF2_SHIFT 10 /**< Shift value for TIMER_ICBOF2 */
-#define _TIMER_IF_ICBOF2_MASK 0x400UL /**< Bit mask for TIMER_ICBOF2 */
-#define _TIMER_IF_ICBOF2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IF */
-#define TIMER_IF_ICBOF2_DEFAULT (_TIMER_IF_ICBOF2_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_IF */
-
-/* Bit fields for TIMER IFS */
-#define _TIMER_IFS_RESETVALUE 0x00000000UL /**< Default value for TIMER_IFS */
-#define _TIMER_IFS_MASK 0x00000773UL /**< Mask for TIMER_IFS */
-#define TIMER_IFS_OF (0x1UL << 0) /**< Overflow Interrupt Flag Set */
-#define _TIMER_IFS_OF_SHIFT 0 /**< Shift value for TIMER_OF */
-#define _TIMER_IFS_OF_MASK 0x1UL /**< Bit mask for TIMER_OF */
-#define _TIMER_IFS_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_OF_DEFAULT (_TIMER_IFS_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_UF (0x1UL << 1) /**< Underflow Interrupt Flag Set */
-#define _TIMER_IFS_UF_SHIFT 1 /**< Shift value for TIMER_UF */
-#define _TIMER_IFS_UF_MASK 0x2UL /**< Bit mask for TIMER_UF */
-#define _TIMER_IFS_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_UF_DEFAULT (_TIMER_IFS_UF_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_CC0 (0x1UL << 4) /**< CC Channel 0 Interrupt Flag Set */
-#define _TIMER_IFS_CC0_SHIFT 4 /**< Shift value for TIMER_CC0 */
-#define _TIMER_IFS_CC0_MASK 0x10UL /**< Bit mask for TIMER_CC0 */
-#define _TIMER_IFS_CC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_CC0_DEFAULT (_TIMER_IFS_CC0_DEFAULT << 4) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_CC1 (0x1UL << 5) /**< CC Channel 1 Interrupt Flag Set */
-#define _TIMER_IFS_CC1_SHIFT 5 /**< Shift value for TIMER_CC1 */
-#define _TIMER_IFS_CC1_MASK 0x20UL /**< Bit mask for TIMER_CC1 */
-#define _TIMER_IFS_CC1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_CC1_DEFAULT (_TIMER_IFS_CC1_DEFAULT << 5) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_CC2 (0x1UL << 6) /**< CC Channel 2 Interrupt Flag Set */
-#define _TIMER_IFS_CC2_SHIFT 6 /**< Shift value for TIMER_CC2 */
-#define _TIMER_IFS_CC2_MASK 0x40UL /**< Bit mask for TIMER_CC2 */
-#define _TIMER_IFS_CC2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_CC2_DEFAULT (_TIMER_IFS_CC2_DEFAULT << 6) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_ICBOF0 (0x1UL << 8) /**< CC Channel 0 Input Capture Buffer Overflow Interrupt Flag Set */
-#define _TIMER_IFS_ICBOF0_SHIFT 8 /**< Shift value for TIMER_ICBOF0 */
-#define _TIMER_IFS_ICBOF0_MASK 0x100UL /**< Bit mask for TIMER_ICBOF0 */
-#define _TIMER_IFS_ICBOF0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_ICBOF0_DEFAULT (_TIMER_IFS_ICBOF0_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_ICBOF1 (0x1UL << 9) /**< CC Channel 1 Input Capture Buffer Overflow Interrupt Flag Set */
-#define _TIMER_IFS_ICBOF1_SHIFT 9 /**< Shift value for TIMER_ICBOF1 */
-#define _TIMER_IFS_ICBOF1_MASK 0x200UL /**< Bit mask for TIMER_ICBOF1 */
-#define _TIMER_IFS_ICBOF1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_ICBOF1_DEFAULT (_TIMER_IFS_ICBOF1_DEFAULT << 9) /**< Shifted mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_ICBOF2 (0x1UL << 10) /**< CC Channel 2 Input Capture Buffer Overflow Interrupt Flag Set */
-#define _TIMER_IFS_ICBOF2_SHIFT 10 /**< Shift value for TIMER_ICBOF2 */
-#define _TIMER_IFS_ICBOF2_MASK 0x400UL /**< Bit mask for TIMER_ICBOF2 */
-#define _TIMER_IFS_ICBOF2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFS */
-#define TIMER_IFS_ICBOF2_DEFAULT (_TIMER_IFS_ICBOF2_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_IFS */
-
-/* Bit fields for TIMER IFC */
-#define _TIMER_IFC_RESETVALUE 0x00000000UL /**< Default value for TIMER_IFC */
-#define _TIMER_IFC_MASK 0x00000773UL /**< Mask for TIMER_IFC */
-#define TIMER_IFC_OF (0x1UL << 0) /**< Overflow Interrupt Flag Clear */
-#define _TIMER_IFC_OF_SHIFT 0 /**< Shift value for TIMER_OF */
-#define _TIMER_IFC_OF_MASK 0x1UL /**< Bit mask for TIMER_OF */
-#define _TIMER_IFC_OF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_OF_DEFAULT (_TIMER_IFC_OF_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_UF (0x1UL << 1) /**< Underflow Interrupt Flag Clear */
-#define _TIMER_IFC_UF_SHIFT 1 /**< Shift value for TIMER_UF */
-#define _TIMER_IFC_UF_MASK 0x2UL /**< Bit mask for TIMER_UF */
-#define _TIMER_IFC_UF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_UF_DEFAULT (_TIMER_IFC_UF_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_CC0 (0x1UL << 4) /**< CC Channel 0 Interrupt Flag Clear */
-#define _TIMER_IFC_CC0_SHIFT 4 /**< Shift value for TIMER_CC0 */
-#define _TIMER_IFC_CC0_MASK 0x10UL /**< Bit mask for TIMER_CC0 */
-#define _TIMER_IFC_CC0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_CC0_DEFAULT (_TIMER_IFC_CC0_DEFAULT << 4) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_CC1 (0x1UL << 5) /**< CC Channel 1 Interrupt Flag Clear */
-#define _TIMER_IFC_CC1_SHIFT 5 /**< Shift value for TIMER_CC1 */
-#define _TIMER_IFC_CC1_MASK 0x20UL /**< Bit mask for TIMER_CC1 */
-#define _TIMER_IFC_CC1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_CC1_DEFAULT (_TIMER_IFC_CC1_DEFAULT << 5) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_CC2 (0x1UL << 6) /**< CC Channel 2 Interrupt Flag Clear */
-#define _TIMER_IFC_CC2_SHIFT 6 /**< Shift value for TIMER_CC2 */
-#define _TIMER_IFC_CC2_MASK 0x40UL /**< Bit mask for TIMER_CC2 */
-#define _TIMER_IFC_CC2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_CC2_DEFAULT (_TIMER_IFC_CC2_DEFAULT << 6) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_ICBOF0 (0x1UL << 8) /**< CC Channel 0 Input Capture Buffer Overflow Interrupt Flag Clear */
-#define _TIMER_IFC_ICBOF0_SHIFT 8 /**< Shift value for TIMER_ICBOF0 */
-#define _TIMER_IFC_ICBOF0_MASK 0x100UL /**< Bit mask for TIMER_ICBOF0 */
-#define _TIMER_IFC_ICBOF0_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_ICBOF0_DEFAULT (_TIMER_IFC_ICBOF0_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_ICBOF1 (0x1UL << 9) /**< CC Channel 1 Input Capture Buffer Overflow Interrupt Flag Clear */
-#define _TIMER_IFC_ICBOF1_SHIFT 9 /**< Shift value for TIMER_ICBOF1 */
-#define _TIMER_IFC_ICBOF1_MASK 0x200UL /**< Bit mask for TIMER_ICBOF1 */
-#define _TIMER_IFC_ICBOF1_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_ICBOF1_DEFAULT (_TIMER_IFC_ICBOF1_DEFAULT << 9) /**< Shifted mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_ICBOF2 (0x1UL << 10) /**< CC Channel 2 Input Capture Buffer Overflow Interrupt Flag Clear */
-#define _TIMER_IFC_ICBOF2_SHIFT 10 /**< Shift value for TIMER_ICBOF2 */
-#define _TIMER_IFC_ICBOF2_MASK 0x400UL /**< Bit mask for TIMER_ICBOF2 */
-#define _TIMER_IFC_ICBOF2_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_IFC */
-#define TIMER_IFC_ICBOF2_DEFAULT (_TIMER_IFC_ICBOF2_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_IFC */
-
-/* Bit fields for TIMER TOP */
-#define _TIMER_TOP_RESETVALUE 0x0000FFFFUL /**< Default value for TIMER_TOP */
-#define _TIMER_TOP_MASK 0x0000FFFFUL /**< Mask for TIMER_TOP */
-#define _TIMER_TOP_TOP_SHIFT 0 /**< Shift value for TIMER_TOP */
-#define _TIMER_TOP_TOP_MASK 0xFFFFUL /**< Bit mask for TIMER_TOP */
-#define _TIMER_TOP_TOP_DEFAULT 0x0000FFFFUL /**< Mode DEFAULT for TIMER_TOP */
-#define TIMER_TOP_TOP_DEFAULT (_TIMER_TOP_TOP_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_TOP */
-
-/* Bit fields for TIMER TOPB */
-#define _TIMER_TOPB_RESETVALUE 0x00000000UL /**< Default value for TIMER_TOPB */
-#define _TIMER_TOPB_MASK 0x0000FFFFUL /**< Mask for TIMER_TOPB */
-#define _TIMER_TOPB_TOPB_SHIFT 0 /**< Shift value for TIMER_TOPB */
-#define _TIMER_TOPB_TOPB_MASK 0xFFFFUL /**< Bit mask for TIMER_TOPB */
-#define _TIMER_TOPB_TOPB_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_TOPB */
-#define TIMER_TOPB_TOPB_DEFAULT (_TIMER_TOPB_TOPB_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_TOPB */
-
-/* Bit fields for TIMER CNT */
-#define _TIMER_CNT_RESETVALUE 0x00000000UL /**< Default value for TIMER_CNT */
-#define _TIMER_CNT_MASK 0x0000FFFFUL /**< Mask for TIMER_CNT */
-#define _TIMER_CNT_CNT_SHIFT 0 /**< Shift value for TIMER_CNT */
-#define _TIMER_CNT_CNT_MASK 0xFFFFUL /**< Bit mask for TIMER_CNT */
-#define _TIMER_CNT_CNT_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CNT */
-#define TIMER_CNT_CNT_DEFAULT (_TIMER_CNT_CNT_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CNT */
-
-/* Bit fields for TIMER ROUTE */
-#define _TIMER_ROUTE_RESETVALUE 0x00000000UL /**< Default value for TIMER_ROUTE */
-#define _TIMER_ROUTE_MASK 0x00070007UL /**< Mask for TIMER_ROUTE */
-#define TIMER_ROUTE_CC0PEN (0x1UL << 0) /**< CC Channel 0 Pin Enable */
-#define _TIMER_ROUTE_CC0PEN_SHIFT 0 /**< Shift value for TIMER_CC0PEN */
-#define _TIMER_ROUTE_CC0PEN_MASK 0x1UL /**< Bit mask for TIMER_CC0PEN */
-#define _TIMER_ROUTE_CC0PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_ROUTE */
-#define TIMER_ROUTE_CC0PEN_DEFAULT (_TIMER_ROUTE_CC0PEN_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_ROUTE */
-#define TIMER_ROUTE_CC1PEN (0x1UL << 1) /**< CC Channel 1 Pin Enable */
-#define _TIMER_ROUTE_CC1PEN_SHIFT 1 /**< Shift value for TIMER_CC1PEN */
-#define _TIMER_ROUTE_CC1PEN_MASK 0x2UL /**< Bit mask for TIMER_CC1PEN */
-#define _TIMER_ROUTE_CC1PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_ROUTE */
-#define TIMER_ROUTE_CC1PEN_DEFAULT (_TIMER_ROUTE_CC1PEN_DEFAULT << 1) /**< Shifted mode DEFAULT for TIMER_ROUTE */
-#define TIMER_ROUTE_CC2PEN (0x1UL << 2) /**< CC Channel 2 Pin Enable */
-#define _TIMER_ROUTE_CC2PEN_SHIFT 2 /**< Shift value for TIMER_CC2PEN */
-#define _TIMER_ROUTE_CC2PEN_MASK 0x4UL /**< Bit mask for TIMER_CC2PEN */
-#define _TIMER_ROUTE_CC2PEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_ROUTE */
-#define TIMER_ROUTE_CC2PEN_DEFAULT (_TIMER_ROUTE_CC2PEN_DEFAULT << 2) /**< Shifted mode DEFAULT for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_SHIFT 16 /**< Shift value for TIMER_LOCATION */
-#define _TIMER_ROUTE_LOCATION_MASK 0x70000UL /**< Bit mask for TIMER_LOCATION */
-#define _TIMER_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_LOC3 0x00000003UL /**< Mode LOC3 for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_LOC4 0x00000004UL /**< Mode LOC4 for TIMER_ROUTE */
-#define _TIMER_ROUTE_LOCATION_LOC5 0x00000005UL /**< Mode LOC5 for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_LOC0 (_TIMER_ROUTE_LOCATION_LOC0 << 16) /**< Shifted mode LOC0 for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_DEFAULT (_TIMER_ROUTE_LOCATION_DEFAULT << 16) /**< Shifted mode DEFAULT for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_LOC1 (_TIMER_ROUTE_LOCATION_LOC1 << 16) /**< Shifted mode LOC1 for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_LOC2 (_TIMER_ROUTE_LOCATION_LOC2 << 16) /**< Shifted mode LOC2 for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_LOC3 (_TIMER_ROUTE_LOCATION_LOC3 << 16) /**< Shifted mode LOC3 for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_LOC4 (_TIMER_ROUTE_LOCATION_LOC4 << 16) /**< Shifted mode LOC4 for TIMER_ROUTE */
-#define TIMER_ROUTE_LOCATION_LOC5 (_TIMER_ROUTE_LOCATION_LOC5 << 16) /**< Shifted mode LOC5 for TIMER_ROUTE */
-
-/* Bit fields for TIMER CC_CTRL */
-#define _TIMER_CC_CTRL_RESETVALUE 0x00000000UL /**< Default value for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_MASK 0x1F333F17UL /**< Mask for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_MODE_SHIFT 0 /**< Shift value for TIMER_MODE */
-#define _TIMER_CC_CTRL_MODE_MASK 0x3UL /**< Bit mask for TIMER_MODE */
-#define _TIMER_CC_CTRL_MODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_MODE_OFF 0x00000000UL /**< Mode OFF for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_MODE_INPUTCAPTURE 0x00000001UL /**< Mode INPUTCAPTURE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_MODE_OUTPUTCOMPARE 0x00000002UL /**< Mode OUTPUTCOMPARE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_MODE_PWM 0x00000003UL /**< Mode PWM for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_MODE_DEFAULT (_TIMER_CC_CTRL_MODE_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_MODE_OFF (_TIMER_CC_CTRL_MODE_OFF << 0) /**< Shifted mode OFF for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_MODE_INPUTCAPTURE (_TIMER_CC_CTRL_MODE_INPUTCAPTURE << 0) /**< Shifted mode INPUTCAPTURE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_MODE_OUTPUTCOMPARE (_TIMER_CC_CTRL_MODE_OUTPUTCOMPARE << 0) /**< Shifted mode OUTPUTCOMPARE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_MODE_PWM (_TIMER_CC_CTRL_MODE_PWM << 0) /**< Shifted mode PWM for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_OUTINV (0x1UL << 2) /**< Output Invert */
-#define _TIMER_CC_CTRL_OUTINV_SHIFT 2 /**< Shift value for TIMER_OUTINV */
-#define _TIMER_CC_CTRL_OUTINV_MASK 0x4UL /**< Bit mask for TIMER_OUTINV */
-#define _TIMER_CC_CTRL_OUTINV_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_OUTINV_DEFAULT (_TIMER_CC_CTRL_OUTINV_DEFAULT << 2) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COIST (0x1UL << 4) /**< Compare Output Initial State */
-#define _TIMER_CC_CTRL_COIST_SHIFT 4 /**< Shift value for TIMER_COIST */
-#define _TIMER_CC_CTRL_COIST_MASK 0x10UL /**< Bit mask for TIMER_COIST */
-#define _TIMER_CC_CTRL_COIST_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COIST_DEFAULT (_TIMER_CC_CTRL_COIST_DEFAULT << 4) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CMOA_SHIFT 8 /**< Shift value for TIMER_CMOA */
-#define _TIMER_CC_CTRL_CMOA_MASK 0x300UL /**< Bit mask for TIMER_CMOA */
-#define _TIMER_CC_CTRL_CMOA_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CMOA_NONE 0x00000000UL /**< Mode NONE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CMOA_TOGGLE 0x00000001UL /**< Mode TOGGLE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CMOA_CLEAR 0x00000002UL /**< Mode CLEAR for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CMOA_SET 0x00000003UL /**< Mode SET for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CMOA_DEFAULT (_TIMER_CC_CTRL_CMOA_DEFAULT << 8) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CMOA_NONE (_TIMER_CC_CTRL_CMOA_NONE << 8) /**< Shifted mode NONE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CMOA_TOGGLE (_TIMER_CC_CTRL_CMOA_TOGGLE << 8) /**< Shifted mode TOGGLE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CMOA_CLEAR (_TIMER_CC_CTRL_CMOA_CLEAR << 8) /**< Shifted mode CLEAR for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CMOA_SET (_TIMER_CC_CTRL_CMOA_SET << 8) /**< Shifted mode SET for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_COFOA_SHIFT 10 /**< Shift value for TIMER_COFOA */
-#define _TIMER_CC_CTRL_COFOA_MASK 0xC00UL /**< Bit mask for TIMER_COFOA */
-#define _TIMER_CC_CTRL_COFOA_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_COFOA_NONE 0x00000000UL /**< Mode NONE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_COFOA_TOGGLE 0x00000001UL /**< Mode TOGGLE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_COFOA_CLEAR 0x00000002UL /**< Mode CLEAR for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_COFOA_SET 0x00000003UL /**< Mode SET for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COFOA_DEFAULT (_TIMER_CC_CTRL_COFOA_DEFAULT << 10) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COFOA_NONE (_TIMER_CC_CTRL_COFOA_NONE << 10) /**< Shifted mode NONE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COFOA_TOGGLE (_TIMER_CC_CTRL_COFOA_TOGGLE << 10) /**< Shifted mode TOGGLE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COFOA_CLEAR (_TIMER_CC_CTRL_COFOA_CLEAR << 10) /**< Shifted mode CLEAR for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_COFOA_SET (_TIMER_CC_CTRL_COFOA_SET << 10) /**< Shifted mode SET for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CUFOA_SHIFT 12 /**< Shift value for TIMER_CUFOA */
-#define _TIMER_CC_CTRL_CUFOA_MASK 0x3000UL /**< Bit mask for TIMER_CUFOA */
-#define _TIMER_CC_CTRL_CUFOA_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CUFOA_NONE 0x00000000UL /**< Mode NONE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CUFOA_TOGGLE 0x00000001UL /**< Mode TOGGLE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CUFOA_CLEAR 0x00000002UL /**< Mode CLEAR for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_CUFOA_SET 0x00000003UL /**< Mode SET for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CUFOA_DEFAULT (_TIMER_CC_CTRL_CUFOA_DEFAULT << 12) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CUFOA_NONE (_TIMER_CC_CTRL_CUFOA_NONE << 12) /**< Shifted mode NONE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CUFOA_TOGGLE (_TIMER_CC_CTRL_CUFOA_TOGGLE << 12) /**< Shifted mode TOGGLE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CUFOA_CLEAR (_TIMER_CC_CTRL_CUFOA_CLEAR << 12) /**< Shifted mode CLEAR for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_CUFOA_SET (_TIMER_CC_CTRL_CUFOA_SET << 12) /**< Shifted mode SET for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSSEL_SHIFT 16 /**< Shift value for TIMER_PRSSEL */
-#define _TIMER_CC_CTRL_PRSSEL_MASK 0x30000UL /**< Bit mask for TIMER_PRSSEL */
-#define _TIMER_CC_CTRL_PRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSSEL_DEFAULT (_TIMER_CC_CTRL_PRSSEL_DEFAULT << 16) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSSEL_PRSCH0 (_TIMER_CC_CTRL_PRSSEL_PRSCH0 << 16) /**< Shifted mode PRSCH0 for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSSEL_PRSCH1 (_TIMER_CC_CTRL_PRSSEL_PRSCH1 << 16) /**< Shifted mode PRSCH1 for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSSEL_PRSCH2 (_TIMER_CC_CTRL_PRSSEL_PRSCH2 << 16) /**< Shifted mode PRSCH2 for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSSEL_PRSCH3 (_TIMER_CC_CTRL_PRSSEL_PRSCH3 << 16) /**< Shifted mode PRSCH3 for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_INSEL (0x1UL << 20) /**< Input Selection */
-#define _TIMER_CC_CTRL_INSEL_SHIFT 20 /**< Shift value for TIMER_INSEL */
-#define _TIMER_CC_CTRL_INSEL_MASK 0x100000UL /**< Bit mask for TIMER_INSEL */
-#define _TIMER_CC_CTRL_INSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_INSEL_PIN 0x00000000UL /**< Mode PIN for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_INSEL_PRS 0x00000001UL /**< Mode PRS for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_INSEL_DEFAULT (_TIMER_CC_CTRL_INSEL_DEFAULT << 20) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_INSEL_PIN (_TIMER_CC_CTRL_INSEL_PIN << 20) /**< Shifted mode PIN for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_INSEL_PRS (_TIMER_CC_CTRL_INSEL_PRS << 20) /**< Shifted mode PRS for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_FILT (0x1UL << 21) /**< Digital Filter */
-#define _TIMER_CC_CTRL_FILT_SHIFT 21 /**< Shift value for TIMER_FILT */
-#define _TIMER_CC_CTRL_FILT_MASK 0x200000UL /**< Bit mask for TIMER_FILT */
-#define _TIMER_CC_CTRL_FILT_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_FILT_DISABLE 0x00000000UL /**< Mode DISABLE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_FILT_ENABLE 0x00000001UL /**< Mode ENABLE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_FILT_DEFAULT (_TIMER_CC_CTRL_FILT_DEFAULT << 21) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_FILT_DISABLE (_TIMER_CC_CTRL_FILT_DISABLE << 21) /**< Shifted mode DISABLE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_FILT_ENABLE (_TIMER_CC_CTRL_FILT_ENABLE << 21) /**< Shifted mode ENABLE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEDGE_SHIFT 24 /**< Shift value for TIMER_ICEDGE */
-#define _TIMER_CC_CTRL_ICEDGE_MASK 0x3000000UL /**< Bit mask for TIMER_ICEDGE */
-#define _TIMER_CC_CTRL_ICEDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEDGE_RISING 0x00000000UL /**< Mode RISING for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEDGE_FALLING 0x00000001UL /**< Mode FALLING for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEDGE_BOTH 0x00000002UL /**< Mode BOTH for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEDGE_NONE 0x00000003UL /**< Mode NONE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEDGE_DEFAULT (_TIMER_CC_CTRL_ICEDGE_DEFAULT << 24) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEDGE_RISING (_TIMER_CC_CTRL_ICEDGE_RISING << 24) /**< Shifted mode RISING for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEDGE_FALLING (_TIMER_CC_CTRL_ICEDGE_FALLING << 24) /**< Shifted mode FALLING for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEDGE_BOTH (_TIMER_CC_CTRL_ICEDGE_BOTH << 24) /**< Shifted mode BOTH for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEDGE_NONE (_TIMER_CC_CTRL_ICEDGE_NONE << 24) /**< Shifted mode NONE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_SHIFT 26 /**< Shift value for TIMER_ICEVCTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_MASK 0xC000000UL /**< Bit mask for TIMER_ICEVCTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_EVERYEDGE 0x00000000UL /**< Mode EVERYEDGE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_EVERYSECONDEDGE 0x00000001UL /**< Mode EVERYSECONDEDGE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_RISING 0x00000002UL /**< Mode RISING for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_ICEVCTRL_FALLING 0x00000003UL /**< Mode FALLING for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEVCTRL_DEFAULT (_TIMER_CC_CTRL_ICEVCTRL_DEFAULT << 26) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEVCTRL_EVERYEDGE (_TIMER_CC_CTRL_ICEVCTRL_EVERYEDGE << 26) /**< Shifted mode EVERYEDGE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEVCTRL_EVERYSECONDEDGE (_TIMER_CC_CTRL_ICEVCTRL_EVERYSECONDEDGE << 26) /**< Shifted mode EVERYSECONDEDGE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEVCTRL_RISING (_TIMER_CC_CTRL_ICEVCTRL_RISING << 26) /**< Shifted mode RISING for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_ICEVCTRL_FALLING (_TIMER_CC_CTRL_ICEVCTRL_FALLING << 26) /**< Shifted mode FALLING for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSCONF (0x1UL << 28) /**< PRS Configuration */
-#define _TIMER_CC_CTRL_PRSCONF_SHIFT 28 /**< Shift value for TIMER_PRSCONF */
-#define _TIMER_CC_CTRL_PRSCONF_MASK 0x10000000UL /**< Bit mask for TIMER_PRSCONF */
-#define _TIMER_CC_CTRL_PRSCONF_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSCONF_PULSE 0x00000000UL /**< Mode PULSE for TIMER_CC_CTRL */
-#define _TIMER_CC_CTRL_PRSCONF_LEVEL 0x00000001UL /**< Mode LEVEL for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSCONF_DEFAULT (_TIMER_CC_CTRL_PRSCONF_DEFAULT << 28) /**< Shifted mode DEFAULT for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSCONF_PULSE (_TIMER_CC_CTRL_PRSCONF_PULSE << 28) /**< Shifted mode PULSE for TIMER_CC_CTRL */
-#define TIMER_CC_CTRL_PRSCONF_LEVEL (_TIMER_CC_CTRL_PRSCONF_LEVEL << 28) /**< Shifted mode LEVEL for TIMER_CC_CTRL */
-
-/* Bit fields for TIMER CC_CCV */
-#define _TIMER_CC_CCV_RESETVALUE 0x00000000UL /**< Default value for TIMER_CC_CCV */
-#define _TIMER_CC_CCV_MASK 0x0000FFFFUL /**< Mask for TIMER_CC_CCV */
-#define _TIMER_CC_CCV_CCV_SHIFT 0 /**< Shift value for TIMER_CCV */
-#define _TIMER_CC_CCV_CCV_MASK 0xFFFFUL /**< Bit mask for TIMER_CCV */
-#define _TIMER_CC_CCV_CCV_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CCV */
-#define TIMER_CC_CCV_CCV_DEFAULT (_TIMER_CC_CCV_CCV_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CC_CCV */
-
-/* Bit fields for TIMER CC_CCVP */
-#define _TIMER_CC_CCVP_RESETVALUE 0x00000000UL /**< Default value for TIMER_CC_CCVP */
-#define _TIMER_CC_CCVP_MASK 0x0000FFFFUL /**< Mask for TIMER_CC_CCVP */
-#define _TIMER_CC_CCVP_CCVP_SHIFT 0 /**< Shift value for TIMER_CCVP */
-#define _TIMER_CC_CCVP_CCVP_MASK 0xFFFFUL /**< Bit mask for TIMER_CCVP */
-#define _TIMER_CC_CCVP_CCVP_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CCVP */
-#define TIMER_CC_CCVP_CCVP_DEFAULT (_TIMER_CC_CCVP_CCVP_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CC_CCVP */
-
-/* Bit fields for TIMER CC_CCVB */
-#define _TIMER_CC_CCVB_RESETVALUE 0x00000000UL /**< Default value for TIMER_CC_CCVB */
-#define _TIMER_CC_CCVB_MASK 0x0000FFFFUL /**< Mask for TIMER_CC_CCVB */
-#define _TIMER_CC_CCVB_CCVB_SHIFT 0 /**< Shift value for TIMER_CCVB */
-#define _TIMER_CC_CCVB_CCVB_MASK 0xFFFFUL /**< Bit mask for TIMER_CCVB */
-#define _TIMER_CC_CCVB_CCVB_DEFAULT 0x00000000UL /**< Mode DEFAULT for TIMER_CC_CCVB */
-#define TIMER_CC_CCVB_CCVB_DEFAULT (_TIMER_CC_CCVB_CCVB_DEFAULT << 0) /**< Shifted mode DEFAULT for TIMER_CC_CCVB */
-
-/** @} End of group EFM32ZG_TIMER */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_timer_cc.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_timer_cc.h
deleted file mode 100644
index 7e4236a439..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_timer_cc.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_TIMER_CC register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @brief TIMER_CC EFM32ZG TIMER CC
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< CC Channel Control Register */
- __IOM uint32_t CCV; /**< CC Channel Value Register */
- __IM uint32_t CCVP; /**< CC Channel Value Peek Register */
- __IOM uint32_t CCVB; /**< CC Channel Buffer Register */
-} TIMER_CC_TypeDef;
-
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_usart.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_usart.h
deleted file mode 100644
index e4b25d512b..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_usart.h
+++ /dev/null
@@ -1,1130 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_USART register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_USART
- * @{
- * @brief EFM32ZG_USART Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t FRAME; /**< USART Frame Format Register */
- __IOM uint32_t TRIGCTRL; /**< USART Trigger Control register */
- __IOM uint32_t CMD; /**< Command Register */
- __IM uint32_t STATUS; /**< USART Status Register */
- __IOM uint32_t CLKDIV; /**< Clock Control Register */
- __IM uint32_t RXDATAX; /**< RX Buffer Data Extended Register */
- __IM uint32_t RXDATA; /**< RX Buffer Data Register */
- __IM uint32_t RXDOUBLEX; /**< RX Buffer Double Data Extended Register */
- __IM uint32_t RXDOUBLE; /**< RX FIFO Double Data Register */
- __IM uint32_t RXDATAXP; /**< RX Buffer Data Extended Peek Register */
- __IM uint32_t RXDOUBLEXP; /**< RX Buffer Double Data Extended Peek Register */
- __IOM uint32_t TXDATAX; /**< TX Buffer Data Extended Register */
- __IOM uint32_t TXDATA; /**< TX Buffer Data Register */
- __IOM uint32_t TXDOUBLEX; /**< TX Buffer Double Data Extended Register */
- __IOM uint32_t TXDOUBLE; /**< TX Buffer Double Data Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IOM uint32_t IRCTRL; /**< IrDA Control Register */
- __IOM uint32_t ROUTE; /**< I/O Routing Register */
- __IOM uint32_t INPUT; /**< USART Input Register */
- __IOM uint32_t I2SCTRL; /**< I2S Control Register */
-} USART_TypeDef; /** USART Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_USART_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for USART CTRL */
-#define _USART_CTRL_RESETVALUE 0x00000000UL /**< Default value for USART_CTRL */
-#define _USART_CTRL_MASK 0xFFFFFF7FUL /**< Mask for USART_CTRL */
-#define USART_CTRL_SYNC (0x1UL << 0) /**< USART Synchronous Mode */
-#define _USART_CTRL_SYNC_SHIFT 0 /**< Shift value for USART_SYNC */
-#define _USART_CTRL_SYNC_MASK 0x1UL /**< Bit mask for USART_SYNC */
-#define _USART_CTRL_SYNC_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SYNC_DEFAULT (_USART_CTRL_SYNC_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_LOOPBK (0x1UL << 1) /**< Loopback Enable */
-#define _USART_CTRL_LOOPBK_SHIFT 1 /**< Shift value for USART_LOOPBK */
-#define _USART_CTRL_LOOPBK_MASK 0x2UL /**< Bit mask for USART_LOOPBK */
-#define _USART_CTRL_LOOPBK_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_LOOPBK_DEFAULT (_USART_CTRL_LOOPBK_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CCEN (0x1UL << 2) /**< Collision Check Enable */
-#define _USART_CTRL_CCEN_SHIFT 2 /**< Shift value for USART_CCEN */
-#define _USART_CTRL_CCEN_MASK 0x4UL /**< Bit mask for USART_CCEN */
-#define _USART_CTRL_CCEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CCEN_DEFAULT (_USART_CTRL_CCEN_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MPM (0x1UL << 3) /**< Multi-Processor Mode */
-#define _USART_CTRL_MPM_SHIFT 3 /**< Shift value for USART_MPM */
-#define _USART_CTRL_MPM_MASK 0x8UL /**< Bit mask for USART_MPM */
-#define _USART_CTRL_MPM_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MPM_DEFAULT (_USART_CTRL_MPM_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MPAB (0x1UL << 4) /**< Multi-Processor Address-Bit */
-#define _USART_CTRL_MPAB_SHIFT 4 /**< Shift value for USART_MPAB */
-#define _USART_CTRL_MPAB_MASK 0x10UL /**< Bit mask for USART_MPAB */
-#define _USART_CTRL_MPAB_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MPAB_DEFAULT (_USART_CTRL_MPAB_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_OVS_SHIFT 5 /**< Shift value for USART_OVS */
-#define _USART_CTRL_OVS_MASK 0x60UL /**< Bit mask for USART_OVS */
-#define _USART_CTRL_OVS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_OVS_X16 0x00000000UL /**< Mode X16 for USART_CTRL */
-#define _USART_CTRL_OVS_X8 0x00000001UL /**< Mode X8 for USART_CTRL */
-#define _USART_CTRL_OVS_X6 0x00000002UL /**< Mode X6 for USART_CTRL */
-#define _USART_CTRL_OVS_X4 0x00000003UL /**< Mode X4 for USART_CTRL */
-#define USART_CTRL_OVS_DEFAULT (_USART_CTRL_OVS_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_OVS_X16 (_USART_CTRL_OVS_X16 << 5) /**< Shifted mode X16 for USART_CTRL */
-#define USART_CTRL_OVS_X8 (_USART_CTRL_OVS_X8 << 5) /**< Shifted mode X8 for USART_CTRL */
-#define USART_CTRL_OVS_X6 (_USART_CTRL_OVS_X6 << 5) /**< Shifted mode X6 for USART_CTRL */
-#define USART_CTRL_OVS_X4 (_USART_CTRL_OVS_X4 << 5) /**< Shifted mode X4 for USART_CTRL */
-#define USART_CTRL_CLKPOL (0x1UL << 8) /**< Clock Polarity */
-#define _USART_CTRL_CLKPOL_SHIFT 8 /**< Shift value for USART_CLKPOL */
-#define _USART_CTRL_CLKPOL_MASK 0x100UL /**< Bit mask for USART_CLKPOL */
-#define _USART_CTRL_CLKPOL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_CLKPOL_IDLELOW 0x00000000UL /**< Mode IDLELOW for USART_CTRL */
-#define _USART_CTRL_CLKPOL_IDLEHIGH 0x00000001UL /**< Mode IDLEHIGH for USART_CTRL */
-#define USART_CTRL_CLKPOL_DEFAULT (_USART_CTRL_CLKPOL_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CLKPOL_IDLELOW (_USART_CTRL_CLKPOL_IDLELOW << 8) /**< Shifted mode IDLELOW for USART_CTRL */
-#define USART_CTRL_CLKPOL_IDLEHIGH (_USART_CTRL_CLKPOL_IDLEHIGH << 8) /**< Shifted mode IDLEHIGH for USART_CTRL */
-#define USART_CTRL_CLKPHA (0x1UL << 9) /**< Clock Edge For Setup/Sample */
-#define _USART_CTRL_CLKPHA_SHIFT 9 /**< Shift value for USART_CLKPHA */
-#define _USART_CTRL_CLKPHA_MASK 0x200UL /**< Bit mask for USART_CLKPHA */
-#define _USART_CTRL_CLKPHA_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_CLKPHA_SAMPLELEADING 0x00000000UL /**< Mode SAMPLELEADING for USART_CTRL */
-#define _USART_CTRL_CLKPHA_SAMPLETRAILING 0x00000001UL /**< Mode SAMPLETRAILING for USART_CTRL */
-#define USART_CTRL_CLKPHA_DEFAULT (_USART_CTRL_CLKPHA_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CLKPHA_SAMPLELEADING (_USART_CTRL_CLKPHA_SAMPLELEADING << 9) /**< Shifted mode SAMPLELEADING for USART_CTRL */
-#define USART_CTRL_CLKPHA_SAMPLETRAILING (_USART_CTRL_CLKPHA_SAMPLETRAILING << 9) /**< Shifted mode SAMPLETRAILING for USART_CTRL */
-#define USART_CTRL_MSBF (0x1UL << 10) /**< Most Significant Bit First */
-#define _USART_CTRL_MSBF_SHIFT 10 /**< Shift value for USART_MSBF */
-#define _USART_CTRL_MSBF_MASK 0x400UL /**< Bit mask for USART_MSBF */
-#define _USART_CTRL_MSBF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MSBF_DEFAULT (_USART_CTRL_MSBF_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CSMA (0x1UL << 11) /**< Action On Slave-Select In Master Mode */
-#define _USART_CTRL_CSMA_SHIFT 11 /**< Shift value for USART_CSMA */
-#define _USART_CTRL_CSMA_MASK 0x800UL /**< Bit mask for USART_CSMA */
-#define _USART_CTRL_CSMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_CSMA_NOACTION 0x00000000UL /**< Mode NOACTION for USART_CTRL */
-#define _USART_CTRL_CSMA_GOTOSLAVEMODE 0x00000001UL /**< Mode GOTOSLAVEMODE for USART_CTRL */
-#define USART_CTRL_CSMA_DEFAULT (_USART_CTRL_CSMA_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CSMA_NOACTION (_USART_CTRL_CSMA_NOACTION << 11) /**< Shifted mode NOACTION for USART_CTRL */
-#define USART_CTRL_CSMA_GOTOSLAVEMODE (_USART_CTRL_CSMA_GOTOSLAVEMODE << 11) /**< Shifted mode GOTOSLAVEMODE for USART_CTRL */
-#define USART_CTRL_TXBIL (0x1UL << 12) /**< TX Buffer Interrupt Level */
-#define _USART_CTRL_TXBIL_SHIFT 12 /**< Shift value for USART_TXBIL */
-#define _USART_CTRL_TXBIL_MASK 0x1000UL /**< Bit mask for USART_TXBIL */
-#define _USART_CTRL_TXBIL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_TXBIL_EMPTY 0x00000000UL /**< Mode EMPTY for USART_CTRL */
-#define _USART_CTRL_TXBIL_HALFFULL 0x00000001UL /**< Mode HALFFULL for USART_CTRL */
-#define USART_CTRL_TXBIL_DEFAULT (_USART_CTRL_TXBIL_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_TXBIL_EMPTY (_USART_CTRL_TXBIL_EMPTY << 12) /**< Shifted mode EMPTY for USART_CTRL */
-#define USART_CTRL_TXBIL_HALFFULL (_USART_CTRL_TXBIL_HALFFULL << 12) /**< Shifted mode HALFFULL for USART_CTRL */
-#define USART_CTRL_RXINV (0x1UL << 13) /**< Receiver Input Invert */
-#define _USART_CTRL_RXINV_SHIFT 13 /**< Shift value for USART_RXINV */
-#define _USART_CTRL_RXINV_MASK 0x2000UL /**< Bit mask for USART_RXINV */
-#define _USART_CTRL_RXINV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_RXINV_DEFAULT (_USART_CTRL_RXINV_DEFAULT << 13) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_TXINV (0x1UL << 14) /**< Transmitter output Invert */
-#define _USART_CTRL_TXINV_SHIFT 14 /**< Shift value for USART_TXINV */
-#define _USART_CTRL_TXINV_MASK 0x4000UL /**< Bit mask for USART_TXINV */
-#define _USART_CTRL_TXINV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_TXINV_DEFAULT (_USART_CTRL_TXINV_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CSINV (0x1UL << 15) /**< Chip Select Invert */
-#define _USART_CTRL_CSINV_SHIFT 15 /**< Shift value for USART_CSINV */
-#define _USART_CTRL_CSINV_MASK 0x8000UL /**< Bit mask for USART_CSINV */
-#define _USART_CTRL_CSINV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_CSINV_DEFAULT (_USART_CTRL_CSINV_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_AUTOCS (0x1UL << 16) /**< Automatic Chip Select */
-#define _USART_CTRL_AUTOCS_SHIFT 16 /**< Shift value for USART_AUTOCS */
-#define _USART_CTRL_AUTOCS_MASK 0x10000UL /**< Bit mask for USART_AUTOCS */
-#define _USART_CTRL_AUTOCS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_AUTOCS_DEFAULT (_USART_CTRL_AUTOCS_DEFAULT << 16) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_AUTOTRI (0x1UL << 17) /**< Automatic TX Tristate */
-#define _USART_CTRL_AUTOTRI_SHIFT 17 /**< Shift value for USART_AUTOTRI */
-#define _USART_CTRL_AUTOTRI_MASK 0x20000UL /**< Bit mask for USART_AUTOTRI */
-#define _USART_CTRL_AUTOTRI_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_AUTOTRI_DEFAULT (_USART_CTRL_AUTOTRI_DEFAULT << 17) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SCMODE (0x1UL << 18) /**< SmartCard Mode */
-#define _USART_CTRL_SCMODE_SHIFT 18 /**< Shift value for USART_SCMODE */
-#define _USART_CTRL_SCMODE_MASK 0x40000UL /**< Bit mask for USART_SCMODE */
-#define _USART_CTRL_SCMODE_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SCMODE_DEFAULT (_USART_CTRL_SCMODE_DEFAULT << 18) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SCRETRANS (0x1UL << 19) /**< SmartCard Retransmit */
-#define _USART_CTRL_SCRETRANS_SHIFT 19 /**< Shift value for USART_SCRETRANS */
-#define _USART_CTRL_SCRETRANS_MASK 0x80000UL /**< Bit mask for USART_SCRETRANS */
-#define _USART_CTRL_SCRETRANS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SCRETRANS_DEFAULT (_USART_CTRL_SCRETRANS_DEFAULT << 19) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SKIPPERRF (0x1UL << 20) /**< Skip Parity Error Frames */
-#define _USART_CTRL_SKIPPERRF_SHIFT 20 /**< Shift value for USART_SKIPPERRF */
-#define _USART_CTRL_SKIPPERRF_MASK 0x100000UL /**< Bit mask for USART_SKIPPERRF */
-#define _USART_CTRL_SKIPPERRF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SKIPPERRF_DEFAULT (_USART_CTRL_SKIPPERRF_DEFAULT << 20) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_BIT8DV (0x1UL << 21) /**< Bit 8 Default Value */
-#define _USART_CTRL_BIT8DV_SHIFT 21 /**< Shift value for USART_BIT8DV */
-#define _USART_CTRL_BIT8DV_MASK 0x200000UL /**< Bit mask for USART_BIT8DV */
-#define _USART_CTRL_BIT8DV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_BIT8DV_DEFAULT (_USART_CTRL_BIT8DV_DEFAULT << 21) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_ERRSDMA (0x1UL << 22) /**< Halt DMA On Error */
-#define _USART_CTRL_ERRSDMA_SHIFT 22 /**< Shift value for USART_ERRSDMA */
-#define _USART_CTRL_ERRSDMA_MASK 0x400000UL /**< Bit mask for USART_ERRSDMA */
-#define _USART_CTRL_ERRSDMA_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_ERRSDMA_DEFAULT (_USART_CTRL_ERRSDMA_DEFAULT << 22) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_ERRSRX (0x1UL << 23) /**< Disable RX On Error */
-#define _USART_CTRL_ERRSRX_SHIFT 23 /**< Shift value for USART_ERRSRX */
-#define _USART_CTRL_ERRSRX_MASK 0x800000UL /**< Bit mask for USART_ERRSRX */
-#define _USART_CTRL_ERRSRX_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_ERRSRX_DEFAULT (_USART_CTRL_ERRSRX_DEFAULT << 23) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_ERRSTX (0x1UL << 24) /**< Disable TX On Error */
-#define _USART_CTRL_ERRSTX_SHIFT 24 /**< Shift value for USART_ERRSTX */
-#define _USART_CTRL_ERRSTX_MASK 0x1000000UL /**< Bit mask for USART_ERRSTX */
-#define _USART_CTRL_ERRSTX_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_ERRSTX_DEFAULT (_USART_CTRL_ERRSTX_DEFAULT << 24) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SSSEARLY (0x1UL << 25) /**< Synchronous Slave Setup Early */
-#define _USART_CTRL_SSSEARLY_SHIFT 25 /**< Shift value for USART_SSSEARLY */
-#define _USART_CTRL_SSSEARLY_MASK 0x2000000UL /**< Bit mask for USART_SSSEARLY */
-#define _USART_CTRL_SSSEARLY_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SSSEARLY_DEFAULT (_USART_CTRL_SSSEARLY_DEFAULT << 25) /**< Shifted mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_TXDELAY_SHIFT 26 /**< Shift value for USART_TXDELAY */
-#define _USART_CTRL_TXDELAY_MASK 0xC000000UL /**< Bit mask for USART_TXDELAY */
-#define _USART_CTRL_TXDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define _USART_CTRL_TXDELAY_NONE 0x00000000UL /**< Mode NONE for USART_CTRL */
-#define _USART_CTRL_TXDELAY_SINGLE 0x00000001UL /**< Mode SINGLE for USART_CTRL */
-#define _USART_CTRL_TXDELAY_DOUBLE 0x00000002UL /**< Mode DOUBLE for USART_CTRL */
-#define _USART_CTRL_TXDELAY_TRIPLE 0x00000003UL /**< Mode TRIPLE for USART_CTRL */
-#define USART_CTRL_TXDELAY_DEFAULT (_USART_CTRL_TXDELAY_DEFAULT << 26) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_TXDELAY_NONE (_USART_CTRL_TXDELAY_NONE << 26) /**< Shifted mode NONE for USART_CTRL */
-#define USART_CTRL_TXDELAY_SINGLE (_USART_CTRL_TXDELAY_SINGLE << 26) /**< Shifted mode SINGLE for USART_CTRL */
-#define USART_CTRL_TXDELAY_DOUBLE (_USART_CTRL_TXDELAY_DOUBLE << 26) /**< Shifted mode DOUBLE for USART_CTRL */
-#define USART_CTRL_TXDELAY_TRIPLE (_USART_CTRL_TXDELAY_TRIPLE << 26) /**< Shifted mode TRIPLE for USART_CTRL */
-#define USART_CTRL_BYTESWAP (0x1UL << 28) /**< Byteswap In Double Accesses */
-#define _USART_CTRL_BYTESWAP_SHIFT 28 /**< Shift value for USART_BYTESWAP */
-#define _USART_CTRL_BYTESWAP_MASK 0x10000000UL /**< Bit mask for USART_BYTESWAP */
-#define _USART_CTRL_BYTESWAP_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_BYTESWAP_DEFAULT (_USART_CTRL_BYTESWAP_DEFAULT << 28) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_AUTOTX (0x1UL << 29) /**< Always Transmit When RX Not Full */
-#define _USART_CTRL_AUTOTX_SHIFT 29 /**< Shift value for USART_AUTOTX */
-#define _USART_CTRL_AUTOTX_MASK 0x20000000UL /**< Bit mask for USART_AUTOTX */
-#define _USART_CTRL_AUTOTX_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_AUTOTX_DEFAULT (_USART_CTRL_AUTOTX_DEFAULT << 29) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MVDIS (0x1UL << 30) /**< Majority Vote Disable */
-#define _USART_CTRL_MVDIS_SHIFT 30 /**< Shift value for USART_MVDIS */
-#define _USART_CTRL_MVDIS_MASK 0x40000000UL /**< Bit mask for USART_MVDIS */
-#define _USART_CTRL_MVDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_MVDIS_DEFAULT (_USART_CTRL_MVDIS_DEFAULT << 30) /**< Shifted mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SMSDELAY (0x1UL << 31) /**< Synchronous Master Sample Delay */
-#define _USART_CTRL_SMSDELAY_SHIFT 31 /**< Shift value for USART_SMSDELAY */
-#define _USART_CTRL_SMSDELAY_MASK 0x80000000UL /**< Bit mask for USART_SMSDELAY */
-#define _USART_CTRL_SMSDELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CTRL */
-#define USART_CTRL_SMSDELAY_DEFAULT (_USART_CTRL_SMSDELAY_DEFAULT << 31) /**< Shifted mode DEFAULT for USART_CTRL */
-
-/* Bit fields for USART FRAME */
-#define _USART_FRAME_RESETVALUE 0x00001005UL /**< Default value for USART_FRAME */
-#define _USART_FRAME_MASK 0x0000330FUL /**< Mask for USART_FRAME */
-#define _USART_FRAME_DATABITS_SHIFT 0 /**< Shift value for USART_DATABITS */
-#define _USART_FRAME_DATABITS_MASK 0xFUL /**< Bit mask for USART_DATABITS */
-#define _USART_FRAME_DATABITS_FOUR 0x00000001UL /**< Mode FOUR for USART_FRAME */
-#define _USART_FRAME_DATABITS_FIVE 0x00000002UL /**< Mode FIVE for USART_FRAME */
-#define _USART_FRAME_DATABITS_SIX 0x00000003UL /**< Mode SIX for USART_FRAME */
-#define _USART_FRAME_DATABITS_SEVEN 0x00000004UL /**< Mode SEVEN for USART_FRAME */
-#define _USART_FRAME_DATABITS_DEFAULT 0x00000005UL /**< Mode DEFAULT for USART_FRAME */
-#define _USART_FRAME_DATABITS_EIGHT 0x00000005UL /**< Mode EIGHT for USART_FRAME */
-#define _USART_FRAME_DATABITS_NINE 0x00000006UL /**< Mode NINE for USART_FRAME */
-#define _USART_FRAME_DATABITS_TEN 0x00000007UL /**< Mode TEN for USART_FRAME */
-#define _USART_FRAME_DATABITS_ELEVEN 0x00000008UL /**< Mode ELEVEN for USART_FRAME */
-#define _USART_FRAME_DATABITS_TWELVE 0x00000009UL /**< Mode TWELVE for USART_FRAME */
-#define _USART_FRAME_DATABITS_THIRTEEN 0x0000000AUL /**< Mode THIRTEEN for USART_FRAME */
-#define _USART_FRAME_DATABITS_FOURTEEN 0x0000000BUL /**< Mode FOURTEEN for USART_FRAME */
-#define _USART_FRAME_DATABITS_FIFTEEN 0x0000000CUL /**< Mode FIFTEEN for USART_FRAME */
-#define _USART_FRAME_DATABITS_SIXTEEN 0x0000000DUL /**< Mode SIXTEEN for USART_FRAME */
-#define USART_FRAME_DATABITS_FOUR (_USART_FRAME_DATABITS_FOUR << 0) /**< Shifted mode FOUR for USART_FRAME */
-#define USART_FRAME_DATABITS_FIVE (_USART_FRAME_DATABITS_FIVE << 0) /**< Shifted mode FIVE for USART_FRAME */
-#define USART_FRAME_DATABITS_SIX (_USART_FRAME_DATABITS_SIX << 0) /**< Shifted mode SIX for USART_FRAME */
-#define USART_FRAME_DATABITS_SEVEN (_USART_FRAME_DATABITS_SEVEN << 0) /**< Shifted mode SEVEN for USART_FRAME */
-#define USART_FRAME_DATABITS_DEFAULT (_USART_FRAME_DATABITS_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_FRAME */
-#define USART_FRAME_DATABITS_EIGHT (_USART_FRAME_DATABITS_EIGHT << 0) /**< Shifted mode EIGHT for USART_FRAME */
-#define USART_FRAME_DATABITS_NINE (_USART_FRAME_DATABITS_NINE << 0) /**< Shifted mode NINE for USART_FRAME */
-#define USART_FRAME_DATABITS_TEN (_USART_FRAME_DATABITS_TEN << 0) /**< Shifted mode TEN for USART_FRAME */
-#define USART_FRAME_DATABITS_ELEVEN (_USART_FRAME_DATABITS_ELEVEN << 0) /**< Shifted mode ELEVEN for USART_FRAME */
-#define USART_FRAME_DATABITS_TWELVE (_USART_FRAME_DATABITS_TWELVE << 0) /**< Shifted mode TWELVE for USART_FRAME */
-#define USART_FRAME_DATABITS_THIRTEEN (_USART_FRAME_DATABITS_THIRTEEN << 0) /**< Shifted mode THIRTEEN for USART_FRAME */
-#define USART_FRAME_DATABITS_FOURTEEN (_USART_FRAME_DATABITS_FOURTEEN << 0) /**< Shifted mode FOURTEEN for USART_FRAME */
-#define USART_FRAME_DATABITS_FIFTEEN (_USART_FRAME_DATABITS_FIFTEEN << 0) /**< Shifted mode FIFTEEN for USART_FRAME */
-#define USART_FRAME_DATABITS_SIXTEEN (_USART_FRAME_DATABITS_SIXTEEN << 0) /**< Shifted mode SIXTEEN for USART_FRAME */
-#define _USART_FRAME_PARITY_SHIFT 8 /**< Shift value for USART_PARITY */
-#define _USART_FRAME_PARITY_MASK 0x300UL /**< Bit mask for USART_PARITY */
-#define _USART_FRAME_PARITY_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_FRAME */
-#define _USART_FRAME_PARITY_NONE 0x00000000UL /**< Mode NONE for USART_FRAME */
-#define _USART_FRAME_PARITY_EVEN 0x00000002UL /**< Mode EVEN for USART_FRAME */
-#define _USART_FRAME_PARITY_ODD 0x00000003UL /**< Mode ODD for USART_FRAME */
-#define USART_FRAME_PARITY_DEFAULT (_USART_FRAME_PARITY_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_FRAME */
-#define USART_FRAME_PARITY_NONE (_USART_FRAME_PARITY_NONE << 8) /**< Shifted mode NONE for USART_FRAME */
-#define USART_FRAME_PARITY_EVEN (_USART_FRAME_PARITY_EVEN << 8) /**< Shifted mode EVEN for USART_FRAME */
-#define USART_FRAME_PARITY_ODD (_USART_FRAME_PARITY_ODD << 8) /**< Shifted mode ODD for USART_FRAME */
-#define _USART_FRAME_STOPBITS_SHIFT 12 /**< Shift value for USART_STOPBITS */
-#define _USART_FRAME_STOPBITS_MASK 0x3000UL /**< Bit mask for USART_STOPBITS */
-#define _USART_FRAME_STOPBITS_HALF 0x00000000UL /**< Mode HALF for USART_FRAME */
-#define _USART_FRAME_STOPBITS_DEFAULT 0x00000001UL /**< Mode DEFAULT for USART_FRAME */
-#define _USART_FRAME_STOPBITS_ONE 0x00000001UL /**< Mode ONE for USART_FRAME */
-#define _USART_FRAME_STOPBITS_ONEANDAHALF 0x00000002UL /**< Mode ONEANDAHALF for USART_FRAME */
-#define _USART_FRAME_STOPBITS_TWO 0x00000003UL /**< Mode TWO for USART_FRAME */
-#define USART_FRAME_STOPBITS_HALF (_USART_FRAME_STOPBITS_HALF << 12) /**< Shifted mode HALF for USART_FRAME */
-#define USART_FRAME_STOPBITS_DEFAULT (_USART_FRAME_STOPBITS_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_FRAME */
-#define USART_FRAME_STOPBITS_ONE (_USART_FRAME_STOPBITS_ONE << 12) /**< Shifted mode ONE for USART_FRAME */
-#define USART_FRAME_STOPBITS_ONEANDAHALF (_USART_FRAME_STOPBITS_ONEANDAHALF << 12) /**< Shifted mode ONEANDAHALF for USART_FRAME */
-#define USART_FRAME_STOPBITS_TWO (_USART_FRAME_STOPBITS_TWO << 12) /**< Shifted mode TWO for USART_FRAME */
-
-/* Bit fields for USART TRIGCTRL */
-#define _USART_TRIGCTRL_RESETVALUE 0x00000000UL /**< Default value for USART_TRIGCTRL */
-#define _USART_TRIGCTRL_MASK 0x00000073UL /**< Mask for USART_TRIGCTRL */
-#define _USART_TRIGCTRL_TSEL_SHIFT 0 /**< Shift value for USART_TSEL */
-#define _USART_TRIGCTRL_TSEL_MASK 0x3UL /**< Bit mask for USART_TSEL */
-#define _USART_TRIGCTRL_TSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TRIGCTRL */
-#define _USART_TRIGCTRL_TSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for USART_TRIGCTRL */
-#define _USART_TRIGCTRL_TSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for USART_TRIGCTRL */
-#define _USART_TRIGCTRL_TSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for USART_TRIGCTRL */
-#define _USART_TRIGCTRL_TSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TSEL_DEFAULT (_USART_TRIGCTRL_TSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TSEL_PRSCH0 (_USART_TRIGCTRL_TSEL_PRSCH0 << 0) /**< Shifted mode PRSCH0 for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TSEL_PRSCH1 (_USART_TRIGCTRL_TSEL_PRSCH1 << 0) /**< Shifted mode PRSCH1 for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TSEL_PRSCH2 (_USART_TRIGCTRL_TSEL_PRSCH2 << 0) /**< Shifted mode PRSCH2 for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TSEL_PRSCH3 (_USART_TRIGCTRL_TSEL_PRSCH3 << 0) /**< Shifted mode PRSCH3 for USART_TRIGCTRL */
-#define USART_TRIGCTRL_RXTEN (0x1UL << 4) /**< Receive Trigger Enable */
-#define _USART_TRIGCTRL_RXTEN_SHIFT 4 /**< Shift value for USART_RXTEN */
-#define _USART_TRIGCTRL_RXTEN_MASK 0x10UL /**< Bit mask for USART_RXTEN */
-#define _USART_TRIGCTRL_RXTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TRIGCTRL */
-#define USART_TRIGCTRL_RXTEN_DEFAULT (_USART_TRIGCTRL_RXTEN_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TXTEN (0x1UL << 5) /**< Transmit Trigger Enable */
-#define _USART_TRIGCTRL_TXTEN_SHIFT 5 /**< Shift value for USART_TXTEN */
-#define _USART_TRIGCTRL_TXTEN_MASK 0x20UL /**< Bit mask for USART_TXTEN */
-#define _USART_TRIGCTRL_TXTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TRIGCTRL */
-#define USART_TRIGCTRL_TXTEN_DEFAULT (_USART_TRIGCTRL_TXTEN_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_TRIGCTRL */
-#define USART_TRIGCTRL_AUTOTXTEN (0x1UL << 6) /**< AUTOTX Trigger Enable */
-#define _USART_TRIGCTRL_AUTOTXTEN_SHIFT 6 /**< Shift value for USART_AUTOTXTEN */
-#define _USART_TRIGCTRL_AUTOTXTEN_MASK 0x40UL /**< Bit mask for USART_AUTOTXTEN */
-#define _USART_TRIGCTRL_AUTOTXTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TRIGCTRL */
-#define USART_TRIGCTRL_AUTOTXTEN_DEFAULT (_USART_TRIGCTRL_AUTOTXTEN_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_TRIGCTRL */
-
-/* Bit fields for USART CMD */
-#define _USART_CMD_RESETVALUE 0x00000000UL /**< Default value for USART_CMD */
-#define _USART_CMD_MASK 0x00000FFFUL /**< Mask for USART_CMD */
-#define USART_CMD_RXEN (0x1UL << 0) /**< Receiver Enable */
-#define _USART_CMD_RXEN_SHIFT 0 /**< Shift value for USART_RXEN */
-#define _USART_CMD_RXEN_MASK 0x1UL /**< Bit mask for USART_RXEN */
-#define _USART_CMD_RXEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_RXEN_DEFAULT (_USART_CMD_RXEN_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_RXDIS (0x1UL << 1) /**< Receiver Disable */
-#define _USART_CMD_RXDIS_SHIFT 1 /**< Shift value for USART_RXDIS */
-#define _USART_CMD_RXDIS_MASK 0x2UL /**< Bit mask for USART_RXDIS */
-#define _USART_CMD_RXDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_RXDIS_DEFAULT (_USART_CMD_RXDIS_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_TXEN (0x1UL << 2) /**< Transmitter Enable */
-#define _USART_CMD_TXEN_SHIFT 2 /**< Shift value for USART_TXEN */
-#define _USART_CMD_TXEN_MASK 0x4UL /**< Bit mask for USART_TXEN */
-#define _USART_CMD_TXEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_TXEN_DEFAULT (_USART_CMD_TXEN_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_TXDIS (0x1UL << 3) /**< Transmitter Disable */
-#define _USART_CMD_TXDIS_SHIFT 3 /**< Shift value for USART_TXDIS */
-#define _USART_CMD_TXDIS_MASK 0x8UL /**< Bit mask for USART_TXDIS */
-#define _USART_CMD_TXDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_TXDIS_DEFAULT (_USART_CMD_TXDIS_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_MASTEREN (0x1UL << 4) /**< Master Enable */
-#define _USART_CMD_MASTEREN_SHIFT 4 /**< Shift value for USART_MASTEREN */
-#define _USART_CMD_MASTEREN_MASK 0x10UL /**< Bit mask for USART_MASTEREN */
-#define _USART_CMD_MASTEREN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_MASTEREN_DEFAULT (_USART_CMD_MASTEREN_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_MASTERDIS (0x1UL << 5) /**< Master Disable */
-#define _USART_CMD_MASTERDIS_SHIFT 5 /**< Shift value for USART_MASTERDIS */
-#define _USART_CMD_MASTERDIS_MASK 0x20UL /**< Bit mask for USART_MASTERDIS */
-#define _USART_CMD_MASTERDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_MASTERDIS_DEFAULT (_USART_CMD_MASTERDIS_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_RXBLOCKEN (0x1UL << 6) /**< Receiver Block Enable */
-#define _USART_CMD_RXBLOCKEN_SHIFT 6 /**< Shift value for USART_RXBLOCKEN */
-#define _USART_CMD_RXBLOCKEN_MASK 0x40UL /**< Bit mask for USART_RXBLOCKEN */
-#define _USART_CMD_RXBLOCKEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_RXBLOCKEN_DEFAULT (_USART_CMD_RXBLOCKEN_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_RXBLOCKDIS (0x1UL << 7) /**< Receiver Block Disable */
-#define _USART_CMD_RXBLOCKDIS_SHIFT 7 /**< Shift value for USART_RXBLOCKDIS */
-#define _USART_CMD_RXBLOCKDIS_MASK 0x80UL /**< Bit mask for USART_RXBLOCKDIS */
-#define _USART_CMD_RXBLOCKDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_RXBLOCKDIS_DEFAULT (_USART_CMD_RXBLOCKDIS_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_TXTRIEN (0x1UL << 8) /**< Transmitter Tristate Enable */
-#define _USART_CMD_TXTRIEN_SHIFT 8 /**< Shift value for USART_TXTRIEN */
-#define _USART_CMD_TXTRIEN_MASK 0x100UL /**< Bit mask for USART_TXTRIEN */
-#define _USART_CMD_TXTRIEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_TXTRIEN_DEFAULT (_USART_CMD_TXTRIEN_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_TXTRIDIS (0x1UL << 9) /**< Transmitter Tristate Disable */
-#define _USART_CMD_TXTRIDIS_SHIFT 9 /**< Shift value for USART_TXTRIDIS */
-#define _USART_CMD_TXTRIDIS_MASK 0x200UL /**< Bit mask for USART_TXTRIDIS */
-#define _USART_CMD_TXTRIDIS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_TXTRIDIS_DEFAULT (_USART_CMD_TXTRIDIS_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_CLEARTX (0x1UL << 10) /**< Clear TX */
-#define _USART_CMD_CLEARTX_SHIFT 10 /**< Shift value for USART_CLEARTX */
-#define _USART_CMD_CLEARTX_MASK 0x400UL /**< Bit mask for USART_CLEARTX */
-#define _USART_CMD_CLEARTX_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_CLEARTX_DEFAULT (_USART_CMD_CLEARTX_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_CMD */
-#define USART_CMD_CLEARRX (0x1UL << 11) /**< Clear RX */
-#define _USART_CMD_CLEARRX_SHIFT 11 /**< Shift value for USART_CLEARRX */
-#define _USART_CMD_CLEARRX_MASK 0x800UL /**< Bit mask for USART_CLEARRX */
-#define _USART_CMD_CLEARRX_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CMD */
-#define USART_CMD_CLEARRX_DEFAULT (_USART_CMD_CLEARRX_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_CMD */
-
-/* Bit fields for USART STATUS */
-#define _USART_STATUS_RESETVALUE 0x00000040UL /**< Default value for USART_STATUS */
-#define _USART_STATUS_MASK 0x00001FFFUL /**< Mask for USART_STATUS */
-#define USART_STATUS_RXENS (0x1UL << 0) /**< Receiver Enable Status */
-#define _USART_STATUS_RXENS_SHIFT 0 /**< Shift value for USART_RXENS */
-#define _USART_STATUS_RXENS_MASK 0x1UL /**< Bit mask for USART_RXENS */
-#define _USART_STATUS_RXENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXENS_DEFAULT (_USART_STATUS_RXENS_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXENS (0x1UL << 1) /**< Transmitter Enable Status */
-#define _USART_STATUS_TXENS_SHIFT 1 /**< Shift value for USART_TXENS */
-#define _USART_STATUS_TXENS_MASK 0x2UL /**< Bit mask for USART_TXENS */
-#define _USART_STATUS_TXENS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXENS_DEFAULT (_USART_STATUS_TXENS_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_MASTER (0x1UL << 2) /**< SPI Master Mode */
-#define _USART_STATUS_MASTER_SHIFT 2 /**< Shift value for USART_MASTER */
-#define _USART_STATUS_MASTER_MASK 0x4UL /**< Bit mask for USART_MASTER */
-#define _USART_STATUS_MASTER_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_MASTER_DEFAULT (_USART_STATUS_MASTER_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXBLOCK (0x1UL << 3) /**< Block Incoming Data */
-#define _USART_STATUS_RXBLOCK_SHIFT 3 /**< Shift value for USART_RXBLOCK */
-#define _USART_STATUS_RXBLOCK_MASK 0x8UL /**< Bit mask for USART_RXBLOCK */
-#define _USART_STATUS_RXBLOCK_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXBLOCK_DEFAULT (_USART_STATUS_RXBLOCK_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXTRI (0x1UL << 4) /**< Transmitter Tristated */
-#define _USART_STATUS_TXTRI_SHIFT 4 /**< Shift value for USART_TXTRI */
-#define _USART_STATUS_TXTRI_MASK 0x10UL /**< Bit mask for USART_TXTRI */
-#define _USART_STATUS_TXTRI_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXTRI_DEFAULT (_USART_STATUS_TXTRI_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXC (0x1UL << 5) /**< TX Complete */
-#define _USART_STATUS_TXC_SHIFT 5 /**< Shift value for USART_TXC */
-#define _USART_STATUS_TXC_MASK 0x20UL /**< Bit mask for USART_TXC */
-#define _USART_STATUS_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXC_DEFAULT (_USART_STATUS_TXC_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXBL (0x1UL << 6) /**< TX Buffer Level */
-#define _USART_STATUS_TXBL_SHIFT 6 /**< Shift value for USART_TXBL */
-#define _USART_STATUS_TXBL_MASK 0x40UL /**< Bit mask for USART_TXBL */
-#define _USART_STATUS_TXBL_DEFAULT 0x00000001UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXBL_DEFAULT (_USART_STATUS_TXBL_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXDATAV (0x1UL << 7) /**< RX Data Valid */
-#define _USART_STATUS_RXDATAV_SHIFT 7 /**< Shift value for USART_RXDATAV */
-#define _USART_STATUS_RXDATAV_MASK 0x80UL /**< Bit mask for USART_RXDATAV */
-#define _USART_STATUS_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXDATAV_DEFAULT (_USART_STATUS_RXDATAV_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXFULL (0x1UL << 8) /**< RX FIFO Full */
-#define _USART_STATUS_RXFULL_SHIFT 8 /**< Shift value for USART_RXFULL */
-#define _USART_STATUS_RXFULL_MASK 0x100UL /**< Bit mask for USART_RXFULL */
-#define _USART_STATUS_RXFULL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXFULL_DEFAULT (_USART_STATUS_RXFULL_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXBDRIGHT (0x1UL << 9) /**< TX Buffer Expects Double Right Data */
-#define _USART_STATUS_TXBDRIGHT_SHIFT 9 /**< Shift value for USART_TXBDRIGHT */
-#define _USART_STATUS_TXBDRIGHT_MASK 0x200UL /**< Bit mask for USART_TXBDRIGHT */
-#define _USART_STATUS_TXBDRIGHT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXBDRIGHT_DEFAULT (_USART_STATUS_TXBDRIGHT_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXBSRIGHT (0x1UL << 10) /**< TX Buffer Expects Single Right Data */
-#define _USART_STATUS_TXBSRIGHT_SHIFT 10 /**< Shift value for USART_TXBSRIGHT */
-#define _USART_STATUS_TXBSRIGHT_MASK 0x400UL /**< Bit mask for USART_TXBSRIGHT */
-#define _USART_STATUS_TXBSRIGHT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_TXBSRIGHT_DEFAULT (_USART_STATUS_TXBSRIGHT_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXDATAVRIGHT (0x1UL << 11) /**< RX Data Right */
-#define _USART_STATUS_RXDATAVRIGHT_SHIFT 11 /**< Shift value for USART_RXDATAVRIGHT */
-#define _USART_STATUS_RXDATAVRIGHT_MASK 0x800UL /**< Bit mask for USART_RXDATAVRIGHT */
-#define _USART_STATUS_RXDATAVRIGHT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXDATAVRIGHT_DEFAULT (_USART_STATUS_RXDATAVRIGHT_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXFULLRIGHT (0x1UL << 12) /**< RX Full of Right Data */
-#define _USART_STATUS_RXFULLRIGHT_SHIFT 12 /**< Shift value for USART_RXFULLRIGHT */
-#define _USART_STATUS_RXFULLRIGHT_MASK 0x1000UL /**< Bit mask for USART_RXFULLRIGHT */
-#define _USART_STATUS_RXFULLRIGHT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_STATUS */
-#define USART_STATUS_RXFULLRIGHT_DEFAULT (_USART_STATUS_RXFULLRIGHT_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_STATUS */
-
-/* Bit fields for USART CLKDIV */
-#define _USART_CLKDIV_RESETVALUE 0x00000000UL /**< Default value for USART_CLKDIV */
-#define _USART_CLKDIV_MASK 0x001FFFC0UL /**< Mask for USART_CLKDIV */
-#define _USART_CLKDIV_DIV_SHIFT 6 /**< Shift value for USART_DIV */
-#define _USART_CLKDIV_DIV_MASK 0x1FFFC0UL /**< Bit mask for USART_DIV */
-#define _USART_CLKDIV_DIV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_CLKDIV */
-#define USART_CLKDIV_DIV_DEFAULT (_USART_CLKDIV_DIV_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_CLKDIV */
-
-/* Bit fields for USART RXDATAX */
-#define _USART_RXDATAX_RESETVALUE 0x00000000UL /**< Default value for USART_RXDATAX */
-#define _USART_RXDATAX_MASK 0x0000C1FFUL /**< Mask for USART_RXDATAX */
-#define _USART_RXDATAX_RXDATA_SHIFT 0 /**< Shift value for USART_RXDATA */
-#define _USART_RXDATAX_RXDATA_MASK 0x1FFUL /**< Bit mask for USART_RXDATA */
-#define _USART_RXDATAX_RXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATAX */
-#define USART_RXDATAX_RXDATA_DEFAULT (_USART_RXDATAX_RXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_RXDATAX */
-#define USART_RXDATAX_PERR (0x1UL << 14) /**< Data Parity Error */
-#define _USART_RXDATAX_PERR_SHIFT 14 /**< Shift value for USART_PERR */
-#define _USART_RXDATAX_PERR_MASK 0x4000UL /**< Bit mask for USART_PERR */
-#define _USART_RXDATAX_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATAX */
-#define USART_RXDATAX_PERR_DEFAULT (_USART_RXDATAX_PERR_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_RXDATAX */
-#define USART_RXDATAX_FERR (0x1UL << 15) /**< Data Framing Error */
-#define _USART_RXDATAX_FERR_SHIFT 15 /**< Shift value for USART_FERR */
-#define _USART_RXDATAX_FERR_MASK 0x8000UL /**< Bit mask for USART_FERR */
-#define _USART_RXDATAX_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATAX */
-#define USART_RXDATAX_FERR_DEFAULT (_USART_RXDATAX_FERR_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_RXDATAX */
-
-/* Bit fields for USART RXDATA */
-#define _USART_RXDATA_RESETVALUE 0x00000000UL /**< Default value for USART_RXDATA */
-#define _USART_RXDATA_MASK 0x000000FFUL /**< Mask for USART_RXDATA */
-#define _USART_RXDATA_RXDATA_SHIFT 0 /**< Shift value for USART_RXDATA */
-#define _USART_RXDATA_RXDATA_MASK 0xFFUL /**< Bit mask for USART_RXDATA */
-#define _USART_RXDATA_RXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATA */
-#define USART_RXDATA_RXDATA_DEFAULT (_USART_RXDATA_RXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_RXDATA */
-
-/* Bit fields for USART RXDOUBLEX */
-#define _USART_RXDOUBLEX_RESETVALUE 0x00000000UL /**< Default value for USART_RXDOUBLEX */
-#define _USART_RXDOUBLEX_MASK 0xC1FFC1FFUL /**< Mask for USART_RXDOUBLEX */
-#define _USART_RXDOUBLEX_RXDATA0_SHIFT 0 /**< Shift value for USART_RXDATA0 */
-#define _USART_RXDOUBLEX_RXDATA0_MASK 0x1FFUL /**< Bit mask for USART_RXDATA0 */
-#define _USART_RXDOUBLEX_RXDATA0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_RXDATA0_DEFAULT (_USART_RXDOUBLEX_RXDATA0_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_PERR0 (0x1UL << 14) /**< Data Parity Error 0 */
-#define _USART_RXDOUBLEX_PERR0_SHIFT 14 /**< Shift value for USART_PERR0 */
-#define _USART_RXDOUBLEX_PERR0_MASK 0x4000UL /**< Bit mask for USART_PERR0 */
-#define _USART_RXDOUBLEX_PERR0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_PERR0_DEFAULT (_USART_RXDOUBLEX_PERR0_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_FERR0 (0x1UL << 15) /**< Data Framing Error 0 */
-#define _USART_RXDOUBLEX_FERR0_SHIFT 15 /**< Shift value for USART_FERR0 */
-#define _USART_RXDOUBLEX_FERR0_MASK 0x8000UL /**< Bit mask for USART_FERR0 */
-#define _USART_RXDOUBLEX_FERR0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_FERR0_DEFAULT (_USART_RXDOUBLEX_FERR0_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_RXDOUBLEX */
-#define _USART_RXDOUBLEX_RXDATA1_SHIFT 16 /**< Shift value for USART_RXDATA1 */
-#define _USART_RXDOUBLEX_RXDATA1_MASK 0x1FF0000UL /**< Bit mask for USART_RXDATA1 */
-#define _USART_RXDOUBLEX_RXDATA1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_RXDATA1_DEFAULT (_USART_RXDOUBLEX_RXDATA1_DEFAULT << 16) /**< Shifted mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_PERR1 (0x1UL << 30) /**< Data Parity Error 1 */
-#define _USART_RXDOUBLEX_PERR1_SHIFT 30 /**< Shift value for USART_PERR1 */
-#define _USART_RXDOUBLEX_PERR1_MASK 0x40000000UL /**< Bit mask for USART_PERR1 */
-#define _USART_RXDOUBLEX_PERR1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_PERR1_DEFAULT (_USART_RXDOUBLEX_PERR1_DEFAULT << 30) /**< Shifted mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_FERR1 (0x1UL << 31) /**< Data Framing Error 1 */
-#define _USART_RXDOUBLEX_FERR1_SHIFT 31 /**< Shift value for USART_FERR1 */
-#define _USART_RXDOUBLEX_FERR1_MASK 0x80000000UL /**< Bit mask for USART_FERR1 */
-#define _USART_RXDOUBLEX_FERR1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEX */
-#define USART_RXDOUBLEX_FERR1_DEFAULT (_USART_RXDOUBLEX_FERR1_DEFAULT << 31) /**< Shifted mode DEFAULT for USART_RXDOUBLEX */
-
-/* Bit fields for USART RXDOUBLE */
-#define _USART_RXDOUBLE_RESETVALUE 0x00000000UL /**< Default value for USART_RXDOUBLE */
-#define _USART_RXDOUBLE_MASK 0x0000FFFFUL /**< Mask for USART_RXDOUBLE */
-#define _USART_RXDOUBLE_RXDATA0_SHIFT 0 /**< Shift value for USART_RXDATA0 */
-#define _USART_RXDOUBLE_RXDATA0_MASK 0xFFUL /**< Bit mask for USART_RXDATA0 */
-#define _USART_RXDOUBLE_RXDATA0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLE */
-#define USART_RXDOUBLE_RXDATA0_DEFAULT (_USART_RXDOUBLE_RXDATA0_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_RXDOUBLE */
-#define _USART_RXDOUBLE_RXDATA1_SHIFT 8 /**< Shift value for USART_RXDATA1 */
-#define _USART_RXDOUBLE_RXDATA1_MASK 0xFF00UL /**< Bit mask for USART_RXDATA1 */
-#define _USART_RXDOUBLE_RXDATA1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLE */
-#define USART_RXDOUBLE_RXDATA1_DEFAULT (_USART_RXDOUBLE_RXDATA1_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_RXDOUBLE */
-
-/* Bit fields for USART RXDATAXP */
-#define _USART_RXDATAXP_RESETVALUE 0x00000000UL /**< Default value for USART_RXDATAXP */
-#define _USART_RXDATAXP_MASK 0x0000C1FFUL /**< Mask for USART_RXDATAXP */
-#define _USART_RXDATAXP_RXDATAP_SHIFT 0 /**< Shift value for USART_RXDATAP */
-#define _USART_RXDATAXP_RXDATAP_MASK 0x1FFUL /**< Bit mask for USART_RXDATAP */
-#define _USART_RXDATAXP_RXDATAP_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATAXP */
-#define USART_RXDATAXP_RXDATAP_DEFAULT (_USART_RXDATAXP_RXDATAP_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_RXDATAXP */
-#define USART_RXDATAXP_PERRP (0x1UL << 14) /**< Data Parity Error Peek */
-#define _USART_RXDATAXP_PERRP_SHIFT 14 /**< Shift value for USART_PERRP */
-#define _USART_RXDATAXP_PERRP_MASK 0x4000UL /**< Bit mask for USART_PERRP */
-#define _USART_RXDATAXP_PERRP_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATAXP */
-#define USART_RXDATAXP_PERRP_DEFAULT (_USART_RXDATAXP_PERRP_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_RXDATAXP */
-#define USART_RXDATAXP_FERRP (0x1UL << 15) /**< Data Framing Error Peek */
-#define _USART_RXDATAXP_FERRP_SHIFT 15 /**< Shift value for USART_FERRP */
-#define _USART_RXDATAXP_FERRP_MASK 0x8000UL /**< Bit mask for USART_FERRP */
-#define _USART_RXDATAXP_FERRP_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDATAXP */
-#define USART_RXDATAXP_FERRP_DEFAULT (_USART_RXDATAXP_FERRP_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_RXDATAXP */
-
-/* Bit fields for USART RXDOUBLEXP */
-#define _USART_RXDOUBLEXP_RESETVALUE 0x00000000UL /**< Default value for USART_RXDOUBLEXP */
-#define _USART_RXDOUBLEXP_MASK 0xC1FFC1FFUL /**< Mask for USART_RXDOUBLEXP */
-#define _USART_RXDOUBLEXP_RXDATAP0_SHIFT 0 /**< Shift value for USART_RXDATAP0 */
-#define _USART_RXDOUBLEXP_RXDATAP0_MASK 0x1FFUL /**< Bit mask for USART_RXDATAP0 */
-#define _USART_RXDOUBLEXP_RXDATAP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_RXDATAP0_DEFAULT (_USART_RXDOUBLEXP_RXDATAP0_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_PERRP0 (0x1UL << 14) /**< Data Parity Error 0 Peek */
-#define _USART_RXDOUBLEXP_PERRP0_SHIFT 14 /**< Shift value for USART_PERRP0 */
-#define _USART_RXDOUBLEXP_PERRP0_MASK 0x4000UL /**< Bit mask for USART_PERRP0 */
-#define _USART_RXDOUBLEXP_PERRP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_PERRP0_DEFAULT (_USART_RXDOUBLEXP_PERRP0_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_FERRP0 (0x1UL << 15) /**< Data Framing Error 0 Peek */
-#define _USART_RXDOUBLEXP_FERRP0_SHIFT 15 /**< Shift value for USART_FERRP0 */
-#define _USART_RXDOUBLEXP_FERRP0_MASK 0x8000UL /**< Bit mask for USART_FERRP0 */
-#define _USART_RXDOUBLEXP_FERRP0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_FERRP0_DEFAULT (_USART_RXDOUBLEXP_FERRP0_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_RXDOUBLEXP */
-#define _USART_RXDOUBLEXP_RXDATAP1_SHIFT 16 /**< Shift value for USART_RXDATAP1 */
-#define _USART_RXDOUBLEXP_RXDATAP1_MASK 0x1FF0000UL /**< Bit mask for USART_RXDATAP1 */
-#define _USART_RXDOUBLEXP_RXDATAP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_RXDATAP1_DEFAULT (_USART_RXDOUBLEXP_RXDATAP1_DEFAULT << 16) /**< Shifted mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_PERRP1 (0x1UL << 30) /**< Data Parity Error 1 Peek */
-#define _USART_RXDOUBLEXP_PERRP1_SHIFT 30 /**< Shift value for USART_PERRP1 */
-#define _USART_RXDOUBLEXP_PERRP1_MASK 0x40000000UL /**< Bit mask for USART_PERRP1 */
-#define _USART_RXDOUBLEXP_PERRP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_PERRP1_DEFAULT (_USART_RXDOUBLEXP_PERRP1_DEFAULT << 30) /**< Shifted mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_FERRP1 (0x1UL << 31) /**< Data Framing Error 1 Peek */
-#define _USART_RXDOUBLEXP_FERRP1_SHIFT 31 /**< Shift value for USART_FERRP1 */
-#define _USART_RXDOUBLEXP_FERRP1_MASK 0x80000000UL /**< Bit mask for USART_FERRP1 */
-#define _USART_RXDOUBLEXP_FERRP1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_RXDOUBLEXP */
-#define USART_RXDOUBLEXP_FERRP1_DEFAULT (_USART_RXDOUBLEXP_FERRP1_DEFAULT << 31) /**< Shifted mode DEFAULT for USART_RXDOUBLEXP */
-
-/* Bit fields for USART TXDATAX */
-#define _USART_TXDATAX_RESETVALUE 0x00000000UL /**< Default value for USART_TXDATAX */
-#define _USART_TXDATAX_MASK 0x0000F9FFUL /**< Mask for USART_TXDATAX */
-#define _USART_TXDATAX_TXDATAX_SHIFT 0 /**< Shift value for USART_TXDATAX */
-#define _USART_TXDATAX_TXDATAX_MASK 0x1FFUL /**< Bit mask for USART_TXDATAX */
-#define _USART_TXDATAX_TXDATAX_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXDATAX_DEFAULT (_USART_TXDATAX_TXDATAX_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_UBRXAT (0x1UL << 11) /**< Unblock RX After Transmission */
-#define _USART_TXDATAX_UBRXAT_SHIFT 11 /**< Shift value for USART_UBRXAT */
-#define _USART_TXDATAX_UBRXAT_MASK 0x800UL /**< Bit mask for USART_UBRXAT */
-#define _USART_TXDATAX_UBRXAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_UBRXAT_DEFAULT (_USART_TXDATAX_UBRXAT_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXTRIAT (0x1UL << 12) /**< Set TXTRI After Transmission */
-#define _USART_TXDATAX_TXTRIAT_SHIFT 12 /**< Shift value for USART_TXTRIAT */
-#define _USART_TXDATAX_TXTRIAT_MASK 0x1000UL /**< Bit mask for USART_TXTRIAT */
-#define _USART_TXDATAX_TXTRIAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXTRIAT_DEFAULT (_USART_TXDATAX_TXTRIAT_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXBREAK (0x1UL << 13) /**< Transmit Data As Break */
-#define _USART_TXDATAX_TXBREAK_SHIFT 13 /**< Shift value for USART_TXBREAK */
-#define _USART_TXDATAX_TXBREAK_MASK 0x2000UL /**< Bit mask for USART_TXBREAK */
-#define _USART_TXDATAX_TXBREAK_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXBREAK_DEFAULT (_USART_TXDATAX_TXBREAK_DEFAULT << 13) /**< Shifted mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXDISAT (0x1UL << 14) /**< Clear TXEN After Transmission */
-#define _USART_TXDATAX_TXDISAT_SHIFT 14 /**< Shift value for USART_TXDISAT */
-#define _USART_TXDATAX_TXDISAT_MASK 0x4000UL /**< Bit mask for USART_TXDISAT */
-#define _USART_TXDATAX_TXDISAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_TXDISAT_DEFAULT (_USART_TXDATAX_TXDISAT_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_RXENAT (0x1UL << 15) /**< Enable RX After Transmission */
-#define _USART_TXDATAX_RXENAT_SHIFT 15 /**< Shift value for USART_RXENAT */
-#define _USART_TXDATAX_RXENAT_MASK 0x8000UL /**< Bit mask for USART_RXENAT */
-#define _USART_TXDATAX_RXENAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATAX */
-#define USART_TXDATAX_RXENAT_DEFAULT (_USART_TXDATAX_RXENAT_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_TXDATAX */
-
-/* Bit fields for USART TXDATA */
-#define _USART_TXDATA_RESETVALUE 0x00000000UL /**< Default value for USART_TXDATA */
-#define _USART_TXDATA_MASK 0x000000FFUL /**< Mask for USART_TXDATA */
-#define _USART_TXDATA_TXDATA_SHIFT 0 /**< Shift value for USART_TXDATA */
-#define _USART_TXDATA_TXDATA_MASK 0xFFUL /**< Bit mask for USART_TXDATA */
-#define _USART_TXDATA_TXDATA_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDATA */
-#define USART_TXDATA_TXDATA_DEFAULT (_USART_TXDATA_TXDATA_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_TXDATA */
-
-/* Bit fields for USART TXDOUBLEX */
-#define _USART_TXDOUBLEX_RESETVALUE 0x00000000UL /**< Default value for USART_TXDOUBLEX */
-#define _USART_TXDOUBLEX_MASK 0xF9FFF9FFUL /**< Mask for USART_TXDOUBLEX */
-#define _USART_TXDOUBLEX_TXDATA0_SHIFT 0 /**< Shift value for USART_TXDATA0 */
-#define _USART_TXDOUBLEX_TXDATA0_MASK 0x1FFUL /**< Bit mask for USART_TXDATA0 */
-#define _USART_TXDOUBLEX_TXDATA0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXDATA0_DEFAULT (_USART_TXDOUBLEX_TXDATA0_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_UBRXAT0 (0x1UL << 11) /**< Unblock RX After Transmission */
-#define _USART_TXDOUBLEX_UBRXAT0_SHIFT 11 /**< Shift value for USART_UBRXAT0 */
-#define _USART_TXDOUBLEX_UBRXAT0_MASK 0x800UL /**< Bit mask for USART_UBRXAT0 */
-#define _USART_TXDOUBLEX_UBRXAT0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_UBRXAT0_DEFAULT (_USART_TXDOUBLEX_UBRXAT0_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXTRIAT0 (0x1UL << 12) /**< Set TXTRI After Transmission */
-#define _USART_TXDOUBLEX_TXTRIAT0_SHIFT 12 /**< Shift value for USART_TXTRIAT0 */
-#define _USART_TXDOUBLEX_TXTRIAT0_MASK 0x1000UL /**< Bit mask for USART_TXTRIAT0 */
-#define _USART_TXDOUBLEX_TXTRIAT0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXTRIAT0_DEFAULT (_USART_TXDOUBLEX_TXTRIAT0_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXBREAK0 (0x1UL << 13) /**< Transmit Data As Break */
-#define _USART_TXDOUBLEX_TXBREAK0_SHIFT 13 /**< Shift value for USART_TXBREAK0 */
-#define _USART_TXDOUBLEX_TXBREAK0_MASK 0x2000UL /**< Bit mask for USART_TXBREAK0 */
-#define _USART_TXDOUBLEX_TXBREAK0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXBREAK0_DEFAULT (_USART_TXDOUBLEX_TXBREAK0_DEFAULT << 13) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXDISAT0 (0x1UL << 14) /**< Clear TXEN After Transmission */
-#define _USART_TXDOUBLEX_TXDISAT0_SHIFT 14 /**< Shift value for USART_TXDISAT0 */
-#define _USART_TXDOUBLEX_TXDISAT0_MASK 0x4000UL /**< Bit mask for USART_TXDISAT0 */
-#define _USART_TXDOUBLEX_TXDISAT0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXDISAT0_DEFAULT (_USART_TXDOUBLEX_TXDISAT0_DEFAULT << 14) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_RXENAT0 (0x1UL << 15) /**< Enable RX After Transmission */
-#define _USART_TXDOUBLEX_RXENAT0_SHIFT 15 /**< Shift value for USART_RXENAT0 */
-#define _USART_TXDOUBLEX_RXENAT0_MASK 0x8000UL /**< Bit mask for USART_RXENAT0 */
-#define _USART_TXDOUBLEX_RXENAT0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_RXENAT0_DEFAULT (_USART_TXDOUBLEX_RXENAT0_DEFAULT << 15) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define _USART_TXDOUBLEX_TXDATA1_SHIFT 16 /**< Shift value for USART_TXDATA1 */
-#define _USART_TXDOUBLEX_TXDATA1_MASK 0x1FF0000UL /**< Bit mask for USART_TXDATA1 */
-#define _USART_TXDOUBLEX_TXDATA1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXDATA1_DEFAULT (_USART_TXDOUBLEX_TXDATA1_DEFAULT << 16) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_UBRXAT1 (0x1UL << 27) /**< Unblock RX After Transmission */
-#define _USART_TXDOUBLEX_UBRXAT1_SHIFT 27 /**< Shift value for USART_UBRXAT1 */
-#define _USART_TXDOUBLEX_UBRXAT1_MASK 0x8000000UL /**< Bit mask for USART_UBRXAT1 */
-#define _USART_TXDOUBLEX_UBRXAT1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_UBRXAT1_DEFAULT (_USART_TXDOUBLEX_UBRXAT1_DEFAULT << 27) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXTRIAT1 (0x1UL << 28) /**< Set TXTRI After Transmission */
-#define _USART_TXDOUBLEX_TXTRIAT1_SHIFT 28 /**< Shift value for USART_TXTRIAT1 */
-#define _USART_TXDOUBLEX_TXTRIAT1_MASK 0x10000000UL /**< Bit mask for USART_TXTRIAT1 */
-#define _USART_TXDOUBLEX_TXTRIAT1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXTRIAT1_DEFAULT (_USART_TXDOUBLEX_TXTRIAT1_DEFAULT << 28) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXBREAK1 (0x1UL << 29) /**< Transmit Data As Break */
-#define _USART_TXDOUBLEX_TXBREAK1_SHIFT 29 /**< Shift value for USART_TXBREAK1 */
-#define _USART_TXDOUBLEX_TXBREAK1_MASK 0x20000000UL /**< Bit mask for USART_TXBREAK1 */
-#define _USART_TXDOUBLEX_TXBREAK1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXBREAK1_DEFAULT (_USART_TXDOUBLEX_TXBREAK1_DEFAULT << 29) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXDISAT1 (0x1UL << 30) /**< Clear TXEN After Transmission */
-#define _USART_TXDOUBLEX_TXDISAT1_SHIFT 30 /**< Shift value for USART_TXDISAT1 */
-#define _USART_TXDOUBLEX_TXDISAT1_MASK 0x40000000UL /**< Bit mask for USART_TXDISAT1 */
-#define _USART_TXDOUBLEX_TXDISAT1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_TXDISAT1_DEFAULT (_USART_TXDOUBLEX_TXDISAT1_DEFAULT << 30) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_RXENAT1 (0x1UL << 31) /**< Enable RX After Transmission */
-#define _USART_TXDOUBLEX_RXENAT1_SHIFT 31 /**< Shift value for USART_RXENAT1 */
-#define _USART_TXDOUBLEX_RXENAT1_MASK 0x80000000UL /**< Bit mask for USART_RXENAT1 */
-#define _USART_TXDOUBLEX_RXENAT1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLEX */
-#define USART_TXDOUBLEX_RXENAT1_DEFAULT (_USART_TXDOUBLEX_RXENAT1_DEFAULT << 31) /**< Shifted mode DEFAULT for USART_TXDOUBLEX */
-
-/* Bit fields for USART TXDOUBLE */
-#define _USART_TXDOUBLE_RESETVALUE 0x00000000UL /**< Default value for USART_TXDOUBLE */
-#define _USART_TXDOUBLE_MASK 0x0000FFFFUL /**< Mask for USART_TXDOUBLE */
-#define _USART_TXDOUBLE_TXDATA0_SHIFT 0 /**< Shift value for USART_TXDATA0 */
-#define _USART_TXDOUBLE_TXDATA0_MASK 0xFFUL /**< Bit mask for USART_TXDATA0 */
-#define _USART_TXDOUBLE_TXDATA0_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLE */
-#define USART_TXDOUBLE_TXDATA0_DEFAULT (_USART_TXDOUBLE_TXDATA0_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_TXDOUBLE */
-#define _USART_TXDOUBLE_TXDATA1_SHIFT 8 /**< Shift value for USART_TXDATA1 */
-#define _USART_TXDOUBLE_TXDATA1_MASK 0xFF00UL /**< Bit mask for USART_TXDATA1 */
-#define _USART_TXDOUBLE_TXDATA1_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_TXDOUBLE */
-#define USART_TXDOUBLE_TXDATA1_DEFAULT (_USART_TXDOUBLE_TXDATA1_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_TXDOUBLE */
-
-/* Bit fields for USART IF */
-#define _USART_IF_RESETVALUE 0x00000002UL /**< Default value for USART_IF */
-#define _USART_IF_MASK 0x00001FFFUL /**< Mask for USART_IF */
-#define USART_IF_TXC (0x1UL << 0) /**< TX Complete Interrupt Flag */
-#define _USART_IF_TXC_SHIFT 0 /**< Shift value for USART_TXC */
-#define _USART_IF_TXC_MASK 0x1UL /**< Bit mask for USART_TXC */
-#define _USART_IF_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_TXC_DEFAULT (_USART_IF_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_TXBL (0x1UL << 1) /**< TX Buffer Level Interrupt Flag */
-#define _USART_IF_TXBL_SHIFT 1 /**< Shift value for USART_TXBL */
-#define _USART_IF_TXBL_MASK 0x2UL /**< Bit mask for USART_TXBL */
-#define _USART_IF_TXBL_DEFAULT 0x00000001UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_TXBL_DEFAULT (_USART_IF_TXBL_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_RXDATAV (0x1UL << 2) /**< RX Data Valid Interrupt Flag */
-#define _USART_IF_RXDATAV_SHIFT 2 /**< Shift value for USART_RXDATAV */
-#define _USART_IF_RXDATAV_MASK 0x4UL /**< Bit mask for USART_RXDATAV */
-#define _USART_IF_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_RXDATAV_DEFAULT (_USART_IF_RXDATAV_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_RXFULL (0x1UL << 3) /**< RX Buffer Full Interrupt Flag */
-#define _USART_IF_RXFULL_SHIFT 3 /**< Shift value for USART_RXFULL */
-#define _USART_IF_RXFULL_MASK 0x8UL /**< Bit mask for USART_RXFULL */
-#define _USART_IF_RXFULL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_RXFULL_DEFAULT (_USART_IF_RXFULL_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_RXOF (0x1UL << 4) /**< RX Overflow Interrupt Flag */
-#define _USART_IF_RXOF_SHIFT 4 /**< Shift value for USART_RXOF */
-#define _USART_IF_RXOF_MASK 0x10UL /**< Bit mask for USART_RXOF */
-#define _USART_IF_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_RXOF_DEFAULT (_USART_IF_RXOF_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_RXUF (0x1UL << 5) /**< RX Underflow Interrupt Flag */
-#define _USART_IF_RXUF_SHIFT 5 /**< Shift value for USART_RXUF */
-#define _USART_IF_RXUF_MASK 0x20UL /**< Bit mask for USART_RXUF */
-#define _USART_IF_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_RXUF_DEFAULT (_USART_IF_RXUF_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_TXOF (0x1UL << 6) /**< TX Overflow Interrupt Flag */
-#define _USART_IF_TXOF_SHIFT 6 /**< Shift value for USART_TXOF */
-#define _USART_IF_TXOF_MASK 0x40UL /**< Bit mask for USART_TXOF */
-#define _USART_IF_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_TXOF_DEFAULT (_USART_IF_TXOF_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_TXUF (0x1UL << 7) /**< TX Underflow Interrupt Flag */
-#define _USART_IF_TXUF_SHIFT 7 /**< Shift value for USART_TXUF */
-#define _USART_IF_TXUF_MASK 0x80UL /**< Bit mask for USART_TXUF */
-#define _USART_IF_TXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_TXUF_DEFAULT (_USART_IF_TXUF_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_PERR (0x1UL << 8) /**< Parity Error Interrupt Flag */
-#define _USART_IF_PERR_SHIFT 8 /**< Shift value for USART_PERR */
-#define _USART_IF_PERR_MASK 0x100UL /**< Bit mask for USART_PERR */
-#define _USART_IF_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_PERR_DEFAULT (_USART_IF_PERR_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_FERR (0x1UL << 9) /**< Framing Error Interrupt Flag */
-#define _USART_IF_FERR_SHIFT 9 /**< Shift value for USART_FERR */
-#define _USART_IF_FERR_MASK 0x200UL /**< Bit mask for USART_FERR */
-#define _USART_IF_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_FERR_DEFAULT (_USART_IF_FERR_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_MPAF (0x1UL << 10) /**< Multi-Processor Address Frame Interrupt Flag */
-#define _USART_IF_MPAF_SHIFT 10 /**< Shift value for USART_MPAF */
-#define _USART_IF_MPAF_MASK 0x400UL /**< Bit mask for USART_MPAF */
-#define _USART_IF_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_MPAF_DEFAULT (_USART_IF_MPAF_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_SSM (0x1UL << 11) /**< Slave-Select In Master Mode Interrupt Flag */
-#define _USART_IF_SSM_SHIFT 11 /**< Shift value for USART_SSM */
-#define _USART_IF_SSM_MASK 0x800UL /**< Bit mask for USART_SSM */
-#define _USART_IF_SSM_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_SSM_DEFAULT (_USART_IF_SSM_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_IF */
-#define USART_IF_CCF (0x1UL << 12) /**< Collision Check Fail Interrupt Flag */
-#define _USART_IF_CCF_SHIFT 12 /**< Shift value for USART_CCF */
-#define _USART_IF_CCF_MASK 0x1000UL /**< Bit mask for USART_CCF */
-#define _USART_IF_CCF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IF */
-#define USART_IF_CCF_DEFAULT (_USART_IF_CCF_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_IF */
-
-/* Bit fields for USART IFS */
-#define _USART_IFS_RESETVALUE 0x00000000UL /**< Default value for USART_IFS */
-#define _USART_IFS_MASK 0x00001FF9UL /**< Mask for USART_IFS */
-#define USART_IFS_TXC (0x1UL << 0) /**< Set TX Complete Interrupt Flag */
-#define _USART_IFS_TXC_SHIFT 0 /**< Shift value for USART_TXC */
-#define _USART_IFS_TXC_MASK 0x1UL /**< Bit mask for USART_TXC */
-#define _USART_IFS_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_TXC_DEFAULT (_USART_IFS_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_RXFULL (0x1UL << 3) /**< Set RX Buffer Full Interrupt Flag */
-#define _USART_IFS_RXFULL_SHIFT 3 /**< Shift value for USART_RXFULL */
-#define _USART_IFS_RXFULL_MASK 0x8UL /**< Bit mask for USART_RXFULL */
-#define _USART_IFS_RXFULL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_RXFULL_DEFAULT (_USART_IFS_RXFULL_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_RXOF (0x1UL << 4) /**< Set RX Overflow Interrupt Flag */
-#define _USART_IFS_RXOF_SHIFT 4 /**< Shift value for USART_RXOF */
-#define _USART_IFS_RXOF_MASK 0x10UL /**< Bit mask for USART_RXOF */
-#define _USART_IFS_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_RXOF_DEFAULT (_USART_IFS_RXOF_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_RXUF (0x1UL << 5) /**< Set RX Underflow Interrupt Flag */
-#define _USART_IFS_RXUF_SHIFT 5 /**< Shift value for USART_RXUF */
-#define _USART_IFS_RXUF_MASK 0x20UL /**< Bit mask for USART_RXUF */
-#define _USART_IFS_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_RXUF_DEFAULT (_USART_IFS_RXUF_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_TXOF (0x1UL << 6) /**< Set TX Overflow Interrupt Flag */
-#define _USART_IFS_TXOF_SHIFT 6 /**< Shift value for USART_TXOF */
-#define _USART_IFS_TXOF_MASK 0x40UL /**< Bit mask for USART_TXOF */
-#define _USART_IFS_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_TXOF_DEFAULT (_USART_IFS_TXOF_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_TXUF (0x1UL << 7) /**< Set TX Underflow Interrupt Flag */
-#define _USART_IFS_TXUF_SHIFT 7 /**< Shift value for USART_TXUF */
-#define _USART_IFS_TXUF_MASK 0x80UL /**< Bit mask for USART_TXUF */
-#define _USART_IFS_TXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_TXUF_DEFAULT (_USART_IFS_TXUF_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_PERR (0x1UL << 8) /**< Set Parity Error Interrupt Flag */
-#define _USART_IFS_PERR_SHIFT 8 /**< Shift value for USART_PERR */
-#define _USART_IFS_PERR_MASK 0x100UL /**< Bit mask for USART_PERR */
-#define _USART_IFS_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_PERR_DEFAULT (_USART_IFS_PERR_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_FERR (0x1UL << 9) /**< Set Framing Error Interrupt Flag */
-#define _USART_IFS_FERR_SHIFT 9 /**< Shift value for USART_FERR */
-#define _USART_IFS_FERR_MASK 0x200UL /**< Bit mask for USART_FERR */
-#define _USART_IFS_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_FERR_DEFAULT (_USART_IFS_FERR_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_MPAF (0x1UL << 10) /**< Set Multi-Processor Address Frame Interrupt Flag */
-#define _USART_IFS_MPAF_SHIFT 10 /**< Shift value for USART_MPAF */
-#define _USART_IFS_MPAF_MASK 0x400UL /**< Bit mask for USART_MPAF */
-#define _USART_IFS_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_MPAF_DEFAULT (_USART_IFS_MPAF_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_SSM (0x1UL << 11) /**< Set Slave-Select in Master mode Interrupt Flag */
-#define _USART_IFS_SSM_SHIFT 11 /**< Shift value for USART_SSM */
-#define _USART_IFS_SSM_MASK 0x800UL /**< Bit mask for USART_SSM */
-#define _USART_IFS_SSM_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_SSM_DEFAULT (_USART_IFS_SSM_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_IFS */
-#define USART_IFS_CCF (0x1UL << 12) /**< Set Collision Check Fail Interrupt Flag */
-#define _USART_IFS_CCF_SHIFT 12 /**< Shift value for USART_CCF */
-#define _USART_IFS_CCF_MASK 0x1000UL /**< Bit mask for USART_CCF */
-#define _USART_IFS_CCF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFS */
-#define USART_IFS_CCF_DEFAULT (_USART_IFS_CCF_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_IFS */
-
-/* Bit fields for USART IFC */
-#define _USART_IFC_RESETVALUE 0x00000000UL /**< Default value for USART_IFC */
-#define _USART_IFC_MASK 0x00001FF9UL /**< Mask for USART_IFC */
-#define USART_IFC_TXC (0x1UL << 0) /**< Clear TX Complete Interrupt Flag */
-#define _USART_IFC_TXC_SHIFT 0 /**< Shift value for USART_TXC */
-#define _USART_IFC_TXC_MASK 0x1UL /**< Bit mask for USART_TXC */
-#define _USART_IFC_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_TXC_DEFAULT (_USART_IFC_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_RXFULL (0x1UL << 3) /**< Clear RX Buffer Full Interrupt Flag */
-#define _USART_IFC_RXFULL_SHIFT 3 /**< Shift value for USART_RXFULL */
-#define _USART_IFC_RXFULL_MASK 0x8UL /**< Bit mask for USART_RXFULL */
-#define _USART_IFC_RXFULL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_RXFULL_DEFAULT (_USART_IFC_RXFULL_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_RXOF (0x1UL << 4) /**< Clear RX Overflow Interrupt Flag */
-#define _USART_IFC_RXOF_SHIFT 4 /**< Shift value for USART_RXOF */
-#define _USART_IFC_RXOF_MASK 0x10UL /**< Bit mask for USART_RXOF */
-#define _USART_IFC_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_RXOF_DEFAULT (_USART_IFC_RXOF_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_RXUF (0x1UL << 5) /**< Clear RX Underflow Interrupt Flag */
-#define _USART_IFC_RXUF_SHIFT 5 /**< Shift value for USART_RXUF */
-#define _USART_IFC_RXUF_MASK 0x20UL /**< Bit mask for USART_RXUF */
-#define _USART_IFC_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_RXUF_DEFAULT (_USART_IFC_RXUF_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_TXOF (0x1UL << 6) /**< Clear TX Overflow Interrupt Flag */
-#define _USART_IFC_TXOF_SHIFT 6 /**< Shift value for USART_TXOF */
-#define _USART_IFC_TXOF_MASK 0x40UL /**< Bit mask for USART_TXOF */
-#define _USART_IFC_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_TXOF_DEFAULT (_USART_IFC_TXOF_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_TXUF (0x1UL << 7) /**< Clear TX Underflow Interrupt Flag */
-#define _USART_IFC_TXUF_SHIFT 7 /**< Shift value for USART_TXUF */
-#define _USART_IFC_TXUF_MASK 0x80UL /**< Bit mask for USART_TXUF */
-#define _USART_IFC_TXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_TXUF_DEFAULT (_USART_IFC_TXUF_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_PERR (0x1UL << 8) /**< Clear Parity Error Interrupt Flag */
-#define _USART_IFC_PERR_SHIFT 8 /**< Shift value for USART_PERR */
-#define _USART_IFC_PERR_MASK 0x100UL /**< Bit mask for USART_PERR */
-#define _USART_IFC_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_PERR_DEFAULT (_USART_IFC_PERR_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_FERR (0x1UL << 9) /**< Clear Framing Error Interrupt Flag */
-#define _USART_IFC_FERR_SHIFT 9 /**< Shift value for USART_FERR */
-#define _USART_IFC_FERR_MASK 0x200UL /**< Bit mask for USART_FERR */
-#define _USART_IFC_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_FERR_DEFAULT (_USART_IFC_FERR_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_MPAF (0x1UL << 10) /**< Clear Multi-Processor Address Frame Interrupt Flag */
-#define _USART_IFC_MPAF_SHIFT 10 /**< Shift value for USART_MPAF */
-#define _USART_IFC_MPAF_MASK 0x400UL /**< Bit mask for USART_MPAF */
-#define _USART_IFC_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_MPAF_DEFAULT (_USART_IFC_MPAF_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_SSM (0x1UL << 11) /**< Clear Slave-Select In Master Mode Interrupt Flag */
-#define _USART_IFC_SSM_SHIFT 11 /**< Shift value for USART_SSM */
-#define _USART_IFC_SSM_MASK 0x800UL /**< Bit mask for USART_SSM */
-#define _USART_IFC_SSM_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_SSM_DEFAULT (_USART_IFC_SSM_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_IFC */
-#define USART_IFC_CCF (0x1UL << 12) /**< Clear Collision Check Fail Interrupt Flag */
-#define _USART_IFC_CCF_SHIFT 12 /**< Shift value for USART_CCF */
-#define _USART_IFC_CCF_MASK 0x1000UL /**< Bit mask for USART_CCF */
-#define _USART_IFC_CCF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IFC */
-#define USART_IFC_CCF_DEFAULT (_USART_IFC_CCF_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_IFC */
-
-/* Bit fields for USART IEN */
-#define _USART_IEN_RESETVALUE 0x00000000UL /**< Default value for USART_IEN */
-#define _USART_IEN_MASK 0x00001FFFUL /**< Mask for USART_IEN */
-#define USART_IEN_TXC (0x1UL << 0) /**< TX Complete Interrupt Enable */
-#define _USART_IEN_TXC_SHIFT 0 /**< Shift value for USART_TXC */
-#define _USART_IEN_TXC_MASK 0x1UL /**< Bit mask for USART_TXC */
-#define _USART_IEN_TXC_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_TXC_DEFAULT (_USART_IEN_TXC_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_TXBL (0x1UL << 1) /**< TX Buffer Level Interrupt Enable */
-#define _USART_IEN_TXBL_SHIFT 1 /**< Shift value for USART_TXBL */
-#define _USART_IEN_TXBL_MASK 0x2UL /**< Bit mask for USART_TXBL */
-#define _USART_IEN_TXBL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_TXBL_DEFAULT (_USART_IEN_TXBL_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_RXDATAV (0x1UL << 2) /**< RX Data Valid Interrupt Enable */
-#define _USART_IEN_RXDATAV_SHIFT 2 /**< Shift value for USART_RXDATAV */
-#define _USART_IEN_RXDATAV_MASK 0x4UL /**< Bit mask for USART_RXDATAV */
-#define _USART_IEN_RXDATAV_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_RXDATAV_DEFAULT (_USART_IEN_RXDATAV_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_RXFULL (0x1UL << 3) /**< RX Buffer Full Interrupt Enable */
-#define _USART_IEN_RXFULL_SHIFT 3 /**< Shift value for USART_RXFULL */
-#define _USART_IEN_RXFULL_MASK 0x8UL /**< Bit mask for USART_RXFULL */
-#define _USART_IEN_RXFULL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_RXFULL_DEFAULT (_USART_IEN_RXFULL_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_RXOF (0x1UL << 4) /**< RX Overflow Interrupt Enable */
-#define _USART_IEN_RXOF_SHIFT 4 /**< Shift value for USART_RXOF */
-#define _USART_IEN_RXOF_MASK 0x10UL /**< Bit mask for USART_RXOF */
-#define _USART_IEN_RXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_RXOF_DEFAULT (_USART_IEN_RXOF_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_RXUF (0x1UL << 5) /**< RX Underflow Interrupt Enable */
-#define _USART_IEN_RXUF_SHIFT 5 /**< Shift value for USART_RXUF */
-#define _USART_IEN_RXUF_MASK 0x20UL /**< Bit mask for USART_RXUF */
-#define _USART_IEN_RXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_RXUF_DEFAULT (_USART_IEN_RXUF_DEFAULT << 5) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_TXOF (0x1UL << 6) /**< TX Overflow Interrupt Enable */
-#define _USART_IEN_TXOF_SHIFT 6 /**< Shift value for USART_TXOF */
-#define _USART_IEN_TXOF_MASK 0x40UL /**< Bit mask for USART_TXOF */
-#define _USART_IEN_TXOF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_TXOF_DEFAULT (_USART_IEN_TXOF_DEFAULT << 6) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_TXUF (0x1UL << 7) /**< TX Underflow Interrupt Enable */
-#define _USART_IEN_TXUF_SHIFT 7 /**< Shift value for USART_TXUF */
-#define _USART_IEN_TXUF_MASK 0x80UL /**< Bit mask for USART_TXUF */
-#define _USART_IEN_TXUF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_TXUF_DEFAULT (_USART_IEN_TXUF_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_PERR (0x1UL << 8) /**< Parity Error Interrupt Enable */
-#define _USART_IEN_PERR_SHIFT 8 /**< Shift value for USART_PERR */
-#define _USART_IEN_PERR_MASK 0x100UL /**< Bit mask for USART_PERR */
-#define _USART_IEN_PERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_PERR_DEFAULT (_USART_IEN_PERR_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_FERR (0x1UL << 9) /**< Framing Error Interrupt Enable */
-#define _USART_IEN_FERR_SHIFT 9 /**< Shift value for USART_FERR */
-#define _USART_IEN_FERR_MASK 0x200UL /**< Bit mask for USART_FERR */
-#define _USART_IEN_FERR_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_FERR_DEFAULT (_USART_IEN_FERR_DEFAULT << 9) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_MPAF (0x1UL << 10) /**< Multi-Processor Address Frame Interrupt Enable */
-#define _USART_IEN_MPAF_SHIFT 10 /**< Shift value for USART_MPAF */
-#define _USART_IEN_MPAF_MASK 0x400UL /**< Bit mask for USART_MPAF */
-#define _USART_IEN_MPAF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_MPAF_DEFAULT (_USART_IEN_MPAF_DEFAULT << 10) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_SSM (0x1UL << 11) /**< Slave-Select In Master Mode Interrupt Enable */
-#define _USART_IEN_SSM_SHIFT 11 /**< Shift value for USART_SSM */
-#define _USART_IEN_SSM_MASK 0x800UL /**< Bit mask for USART_SSM */
-#define _USART_IEN_SSM_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_SSM_DEFAULT (_USART_IEN_SSM_DEFAULT << 11) /**< Shifted mode DEFAULT for USART_IEN */
-#define USART_IEN_CCF (0x1UL << 12) /**< Collision Check Fail Interrupt Enable */
-#define _USART_IEN_CCF_SHIFT 12 /**< Shift value for USART_CCF */
-#define _USART_IEN_CCF_MASK 0x1000UL /**< Bit mask for USART_CCF */
-#define _USART_IEN_CCF_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IEN */
-#define USART_IEN_CCF_DEFAULT (_USART_IEN_CCF_DEFAULT << 12) /**< Shifted mode DEFAULT for USART_IEN */
-
-/* Bit fields for USART IRCTRL */
-#define _USART_IRCTRL_RESETVALUE 0x00000000UL /**< Default value for USART_IRCTRL */
-#define _USART_IRCTRL_MASK 0x000000BFUL /**< Mask for USART_IRCTRL */
-#define USART_IRCTRL_IREN (0x1UL << 0) /**< Enable IrDA Module */
-#define _USART_IRCTRL_IREN_SHIFT 0 /**< Shift value for USART_IREN */
-#define _USART_IRCTRL_IREN_MASK 0x1UL /**< Bit mask for USART_IREN */
-#define _USART_IRCTRL_IREN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IRCTRL */
-#define USART_IRCTRL_IREN_DEFAULT (_USART_IRCTRL_IREN_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_IRCTRL */
-#define _USART_IRCTRL_IRPW_SHIFT 1 /**< Shift value for USART_IRPW */
-#define _USART_IRCTRL_IRPW_MASK 0x6UL /**< Bit mask for USART_IRPW */
-#define _USART_IRCTRL_IRPW_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IRCTRL */
-#define _USART_IRCTRL_IRPW_ONE 0x00000000UL /**< Mode ONE for USART_IRCTRL */
-#define _USART_IRCTRL_IRPW_TWO 0x00000001UL /**< Mode TWO for USART_IRCTRL */
-#define _USART_IRCTRL_IRPW_THREE 0x00000002UL /**< Mode THREE for USART_IRCTRL */
-#define _USART_IRCTRL_IRPW_FOUR 0x00000003UL /**< Mode FOUR for USART_IRCTRL */
-#define USART_IRCTRL_IRPW_DEFAULT (_USART_IRCTRL_IRPW_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_IRCTRL */
-#define USART_IRCTRL_IRPW_ONE (_USART_IRCTRL_IRPW_ONE << 1) /**< Shifted mode ONE for USART_IRCTRL */
-#define USART_IRCTRL_IRPW_TWO (_USART_IRCTRL_IRPW_TWO << 1) /**< Shifted mode TWO for USART_IRCTRL */
-#define USART_IRCTRL_IRPW_THREE (_USART_IRCTRL_IRPW_THREE << 1) /**< Shifted mode THREE for USART_IRCTRL */
-#define USART_IRCTRL_IRPW_FOUR (_USART_IRCTRL_IRPW_FOUR << 1) /**< Shifted mode FOUR for USART_IRCTRL */
-#define USART_IRCTRL_IRFILT (0x1UL << 3) /**< IrDA RX Filter */
-#define _USART_IRCTRL_IRFILT_SHIFT 3 /**< Shift value for USART_IRFILT */
-#define _USART_IRCTRL_IRFILT_MASK 0x8UL /**< Bit mask for USART_IRFILT */
-#define _USART_IRCTRL_IRFILT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IRCTRL */
-#define USART_IRCTRL_IRFILT_DEFAULT (_USART_IRCTRL_IRFILT_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_IRCTRL */
-#define _USART_IRCTRL_IRPRSSEL_SHIFT 4 /**< Shift value for USART_IRPRSSEL */
-#define _USART_IRCTRL_IRPRSSEL_MASK 0x30UL /**< Bit mask for USART_IRPRSSEL */
-#define _USART_IRCTRL_IRPRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IRCTRL */
-#define _USART_IRCTRL_IRPRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for USART_IRCTRL */
-#define _USART_IRCTRL_IRPRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for USART_IRCTRL */
-#define _USART_IRCTRL_IRPRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for USART_IRCTRL */
-#define _USART_IRCTRL_IRPRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSSEL_DEFAULT (_USART_IRCTRL_IRPRSSEL_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSSEL_PRSCH0 (_USART_IRCTRL_IRPRSSEL_PRSCH0 << 4) /**< Shifted mode PRSCH0 for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSSEL_PRSCH1 (_USART_IRCTRL_IRPRSSEL_PRSCH1 << 4) /**< Shifted mode PRSCH1 for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSSEL_PRSCH2 (_USART_IRCTRL_IRPRSSEL_PRSCH2 << 4) /**< Shifted mode PRSCH2 for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSSEL_PRSCH3 (_USART_IRCTRL_IRPRSSEL_PRSCH3 << 4) /**< Shifted mode PRSCH3 for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSEN (0x1UL << 7) /**< IrDA PRS Channel Enable */
-#define _USART_IRCTRL_IRPRSEN_SHIFT 7 /**< Shift value for USART_IRPRSEN */
-#define _USART_IRCTRL_IRPRSEN_MASK 0x80UL /**< Bit mask for USART_IRPRSEN */
-#define _USART_IRCTRL_IRPRSEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_IRCTRL */
-#define USART_IRCTRL_IRPRSEN_DEFAULT (_USART_IRCTRL_IRPRSEN_DEFAULT << 7) /**< Shifted mode DEFAULT for USART_IRCTRL */
-
-/* Bit fields for USART ROUTE */
-#define _USART_ROUTE_RESETVALUE 0x00000000UL /**< Default value for USART_ROUTE */
-#define _USART_ROUTE_MASK 0x0000070FUL /**< Mask for USART_ROUTE */
-#define USART_ROUTE_RXPEN (0x1UL << 0) /**< RX Pin Enable */
-#define _USART_ROUTE_RXPEN_SHIFT 0 /**< Shift value for USART_RXPEN */
-#define _USART_ROUTE_RXPEN_MASK 0x1UL /**< Bit mask for USART_RXPEN */
-#define _USART_ROUTE_RXPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_RXPEN_DEFAULT (_USART_ROUTE_RXPEN_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_TXPEN (0x1UL << 1) /**< TX Pin Enable */
-#define _USART_ROUTE_TXPEN_SHIFT 1 /**< Shift value for USART_TXPEN */
-#define _USART_ROUTE_TXPEN_MASK 0x2UL /**< Bit mask for USART_TXPEN */
-#define _USART_ROUTE_TXPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_TXPEN_DEFAULT (_USART_ROUTE_TXPEN_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_CSPEN (0x1UL << 2) /**< CS Pin Enable */
-#define _USART_ROUTE_CSPEN_SHIFT 2 /**< Shift value for USART_CSPEN */
-#define _USART_ROUTE_CSPEN_MASK 0x4UL /**< Bit mask for USART_CSPEN */
-#define _USART_ROUTE_CSPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_CSPEN_DEFAULT (_USART_ROUTE_CSPEN_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_CLKPEN (0x1UL << 3) /**< CLK Pin Enable */
-#define _USART_ROUTE_CLKPEN_SHIFT 3 /**< Shift value for USART_CLKPEN */
-#define _USART_ROUTE_CLKPEN_MASK 0x8UL /**< Bit mask for USART_CLKPEN */
-#define _USART_ROUTE_CLKPEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_CLKPEN_DEFAULT (_USART_ROUTE_CLKPEN_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_ROUTE */
-#define _USART_ROUTE_LOCATION_SHIFT 8 /**< Shift value for USART_LOCATION */
-#define _USART_ROUTE_LOCATION_MASK 0x700UL /**< Bit mask for USART_LOCATION */
-#define _USART_ROUTE_LOCATION_LOC0 0x00000000UL /**< Mode LOC0 for USART_ROUTE */
-#define _USART_ROUTE_LOCATION_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_ROUTE */
-#define _USART_ROUTE_LOCATION_LOC1 0x00000001UL /**< Mode LOC1 for USART_ROUTE */
-#define _USART_ROUTE_LOCATION_LOC2 0x00000002UL /**< Mode LOC2 for USART_ROUTE */
-#define _USART_ROUTE_LOCATION_LOC3 0x00000003UL /**< Mode LOC3 for USART_ROUTE */
-#define USART_ROUTE_LOCATION_LOC0 (_USART_ROUTE_LOCATION_LOC0 << 8) /**< Shifted mode LOC0 for USART_ROUTE */
-#define USART_ROUTE_LOCATION_DEFAULT (_USART_ROUTE_LOCATION_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_ROUTE */
-#define USART_ROUTE_LOCATION_LOC1 (_USART_ROUTE_LOCATION_LOC1 << 8) /**< Shifted mode LOC1 for USART_ROUTE */
-#define USART_ROUTE_LOCATION_LOC2 (_USART_ROUTE_LOCATION_LOC2 << 8) /**< Shifted mode LOC2 for USART_ROUTE */
-#define USART_ROUTE_LOCATION_LOC3 (_USART_ROUTE_LOCATION_LOC3 << 8) /**< Shifted mode LOC3 for USART_ROUTE */
-
-/* Bit fields for USART INPUT */
-#define _USART_INPUT_RESETVALUE 0x00000000UL /**< Default value for USART_INPUT */
-#define _USART_INPUT_MASK 0x00000013UL /**< Mask for USART_INPUT */
-#define _USART_INPUT_RXPRSSEL_SHIFT 0 /**< Shift value for USART_RXPRSSEL */
-#define _USART_INPUT_RXPRSSEL_MASK 0x3UL /**< Bit mask for USART_RXPRSSEL */
-#define _USART_INPUT_RXPRSSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_INPUT */
-#define _USART_INPUT_RXPRSSEL_PRSCH0 0x00000000UL /**< Mode PRSCH0 for USART_INPUT */
-#define _USART_INPUT_RXPRSSEL_PRSCH1 0x00000001UL /**< Mode PRSCH1 for USART_INPUT */
-#define _USART_INPUT_RXPRSSEL_PRSCH2 0x00000002UL /**< Mode PRSCH2 for USART_INPUT */
-#define _USART_INPUT_RXPRSSEL_PRSCH3 0x00000003UL /**< Mode PRSCH3 for USART_INPUT */
-#define USART_INPUT_RXPRSSEL_DEFAULT (_USART_INPUT_RXPRSSEL_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_INPUT */
-#define USART_INPUT_RXPRSSEL_PRSCH0 (_USART_INPUT_RXPRSSEL_PRSCH0 << 0) /**< Shifted mode PRSCH0 for USART_INPUT */
-#define USART_INPUT_RXPRSSEL_PRSCH1 (_USART_INPUT_RXPRSSEL_PRSCH1 << 0) /**< Shifted mode PRSCH1 for USART_INPUT */
-#define USART_INPUT_RXPRSSEL_PRSCH2 (_USART_INPUT_RXPRSSEL_PRSCH2 << 0) /**< Shifted mode PRSCH2 for USART_INPUT */
-#define USART_INPUT_RXPRSSEL_PRSCH3 (_USART_INPUT_RXPRSSEL_PRSCH3 << 0) /**< Shifted mode PRSCH3 for USART_INPUT */
-#define USART_INPUT_RXPRS (0x1UL << 4) /**< PRS RX Enable */
-#define _USART_INPUT_RXPRS_SHIFT 4 /**< Shift value for USART_RXPRS */
-#define _USART_INPUT_RXPRS_MASK 0x10UL /**< Bit mask for USART_RXPRS */
-#define _USART_INPUT_RXPRS_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_INPUT */
-#define USART_INPUT_RXPRS_DEFAULT (_USART_INPUT_RXPRS_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_INPUT */
-
-/* Bit fields for USART I2SCTRL */
-#define _USART_I2SCTRL_RESETVALUE 0x00000000UL /**< Default value for USART_I2SCTRL */
-#define _USART_I2SCTRL_MASK 0x0000071FUL /**< Mask for USART_I2SCTRL */
-#define USART_I2SCTRL_EN (0x1UL << 0) /**< Enable I2S Mode */
-#define _USART_I2SCTRL_EN_SHIFT 0 /**< Shift value for USART_EN */
-#define _USART_I2SCTRL_EN_MASK 0x1UL /**< Bit mask for USART_EN */
-#define _USART_I2SCTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_EN_DEFAULT (_USART_I2SCTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_MONO (0x1UL << 1) /**< Stero or Mono */
-#define _USART_I2SCTRL_MONO_SHIFT 1 /**< Shift value for USART_MONO */
-#define _USART_I2SCTRL_MONO_MASK 0x2UL /**< Bit mask for USART_MONO */
-#define _USART_I2SCTRL_MONO_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_MONO_DEFAULT (_USART_I2SCTRL_MONO_DEFAULT << 1) /**< Shifted mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_JUSTIFY (0x1UL << 2) /**< Justification of I2S Data */
-#define _USART_I2SCTRL_JUSTIFY_SHIFT 2 /**< Shift value for USART_JUSTIFY */
-#define _USART_I2SCTRL_JUSTIFY_MASK 0x4UL /**< Bit mask for USART_JUSTIFY */
-#define _USART_I2SCTRL_JUSTIFY_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_I2SCTRL */
-#define _USART_I2SCTRL_JUSTIFY_LEFT 0x00000000UL /**< Mode LEFT for USART_I2SCTRL */
-#define _USART_I2SCTRL_JUSTIFY_RIGHT 0x00000001UL /**< Mode RIGHT for USART_I2SCTRL */
-#define USART_I2SCTRL_JUSTIFY_DEFAULT (_USART_I2SCTRL_JUSTIFY_DEFAULT << 2) /**< Shifted mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_JUSTIFY_LEFT (_USART_I2SCTRL_JUSTIFY_LEFT << 2) /**< Shifted mode LEFT for USART_I2SCTRL */
-#define USART_I2SCTRL_JUSTIFY_RIGHT (_USART_I2SCTRL_JUSTIFY_RIGHT << 2) /**< Shifted mode RIGHT for USART_I2SCTRL */
-#define USART_I2SCTRL_DMASPLIT (0x1UL << 3) /**< Separate DMA Request For Left/Right Data */
-#define _USART_I2SCTRL_DMASPLIT_SHIFT 3 /**< Shift value for USART_DMASPLIT */
-#define _USART_I2SCTRL_DMASPLIT_MASK 0x8UL /**< Bit mask for USART_DMASPLIT */
-#define _USART_I2SCTRL_DMASPLIT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_DMASPLIT_DEFAULT (_USART_I2SCTRL_DMASPLIT_DEFAULT << 3) /**< Shifted mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_DELAY (0x1UL << 4) /**< Delay on I2S data */
-#define _USART_I2SCTRL_DELAY_SHIFT 4 /**< Shift value for USART_DELAY */
-#define _USART_I2SCTRL_DELAY_MASK 0x10UL /**< Bit mask for USART_DELAY */
-#define _USART_I2SCTRL_DELAY_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_DELAY_DEFAULT (_USART_I2SCTRL_DELAY_DEFAULT << 4) /**< Shifted mode DEFAULT for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_SHIFT 8 /**< Shift value for USART_FORMAT */
-#define _USART_I2SCTRL_FORMAT_MASK 0x700UL /**< Bit mask for USART_FORMAT */
-#define _USART_I2SCTRL_FORMAT_DEFAULT 0x00000000UL /**< Mode DEFAULT for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W32D32 0x00000000UL /**< Mode W32D32 for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W32D24M 0x00000001UL /**< Mode W32D24M for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W32D24 0x00000002UL /**< Mode W32D24 for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W32D16 0x00000003UL /**< Mode W32D16 for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W32D8 0x00000004UL /**< Mode W32D8 for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W16D16 0x00000005UL /**< Mode W16D16 for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W16D8 0x00000006UL /**< Mode W16D8 for USART_I2SCTRL */
-#define _USART_I2SCTRL_FORMAT_W8D8 0x00000007UL /**< Mode W8D8 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_DEFAULT (_USART_I2SCTRL_FORMAT_DEFAULT << 8) /**< Shifted mode DEFAULT for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W32D32 (_USART_I2SCTRL_FORMAT_W32D32 << 8) /**< Shifted mode W32D32 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W32D24M (_USART_I2SCTRL_FORMAT_W32D24M << 8) /**< Shifted mode W32D24M for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W32D24 (_USART_I2SCTRL_FORMAT_W32D24 << 8) /**< Shifted mode W32D24 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W32D16 (_USART_I2SCTRL_FORMAT_W32D16 << 8) /**< Shifted mode W32D16 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W32D8 (_USART_I2SCTRL_FORMAT_W32D8 << 8) /**< Shifted mode W32D8 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W16D16 (_USART_I2SCTRL_FORMAT_W16D16 << 8) /**< Shifted mode W16D16 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W16D8 (_USART_I2SCTRL_FORMAT_W16D8 << 8) /**< Shifted mode W16D8 for USART_I2SCTRL */
-#define USART_I2SCTRL_FORMAT_W8D8 (_USART_I2SCTRL_FORMAT_W8D8 << 8) /**< Shifted mode W8D8 for USART_I2SCTRL */
-
-/** @} End of group EFM32ZG_USART */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_vcmp.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_vcmp.h
deleted file mode 100644
index e354649747..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_vcmp.h
+++ /dev/null
@@ -1,203 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_VCMP register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_VCMP
- * @{
- * @brief EFM32ZG_VCMP Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t INPUTSEL; /**< Input Selection Register */
- __IM uint32_t STATUS; /**< Status Register */
- __IOM uint32_t IEN; /**< Interrupt Enable Register */
- __IM uint32_t IF; /**< Interrupt Flag Register */
- __IOM uint32_t IFS; /**< Interrupt Flag Set Register */
- __IOM uint32_t IFC; /**< Interrupt Flag Clear Register */
-} VCMP_TypeDef; /** VCMP Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_VCMP_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for VCMP CTRL */
-#define _VCMP_CTRL_RESETVALUE 0x47000000UL /**< Default value for VCMP_CTRL */
-#define _VCMP_CTRL_MASK 0x4F030715UL /**< Mask for VCMP_CTRL */
-#define VCMP_CTRL_EN (0x1UL << 0) /**< Voltage Supply Comparator Enable */
-#define _VCMP_CTRL_EN_SHIFT 0 /**< Shift value for VCMP_EN */
-#define _VCMP_CTRL_EN_MASK 0x1UL /**< Bit mask for VCMP_EN */
-#define _VCMP_CTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_EN_DEFAULT (_VCMP_CTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_INACTVAL (0x1UL << 2) /**< Inactive Value */
-#define _VCMP_CTRL_INACTVAL_SHIFT 2 /**< Shift value for VCMP_INACTVAL */
-#define _VCMP_CTRL_INACTVAL_MASK 0x4UL /**< Bit mask for VCMP_INACTVAL */
-#define _VCMP_CTRL_INACTVAL_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_INACTVAL_DEFAULT (_VCMP_CTRL_INACTVAL_DEFAULT << 2) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_HYSTEN (0x1UL << 4) /**< Hysteresis Enable */
-#define _VCMP_CTRL_HYSTEN_SHIFT 4 /**< Shift value for VCMP_HYSTEN */
-#define _VCMP_CTRL_HYSTEN_MASK 0x10UL /**< Bit mask for VCMP_HYSTEN */
-#define _VCMP_CTRL_HYSTEN_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_HYSTEN_DEFAULT (_VCMP_CTRL_HYSTEN_DEFAULT << 4) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_SHIFT 8 /**< Shift value for VCMP_WARMTIME */
-#define _VCMP_CTRL_WARMTIME_MASK 0x700UL /**< Bit mask for VCMP_WARMTIME */
-#define _VCMP_CTRL_WARMTIME_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_4CYCLES 0x00000000UL /**< Mode 4CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_8CYCLES 0x00000001UL /**< Mode 8CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_16CYCLES 0x00000002UL /**< Mode 16CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_32CYCLES 0x00000003UL /**< Mode 32CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_64CYCLES 0x00000004UL /**< Mode 64CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_128CYCLES 0x00000005UL /**< Mode 128CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_256CYCLES 0x00000006UL /**< Mode 256CYCLES for VCMP_CTRL */
-#define _VCMP_CTRL_WARMTIME_512CYCLES 0x00000007UL /**< Mode 512CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_DEFAULT (_VCMP_CTRL_WARMTIME_DEFAULT << 8) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_4CYCLES (_VCMP_CTRL_WARMTIME_4CYCLES << 8) /**< Shifted mode 4CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_8CYCLES (_VCMP_CTRL_WARMTIME_8CYCLES << 8) /**< Shifted mode 8CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_16CYCLES (_VCMP_CTRL_WARMTIME_16CYCLES << 8) /**< Shifted mode 16CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_32CYCLES (_VCMP_CTRL_WARMTIME_32CYCLES << 8) /**< Shifted mode 32CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_64CYCLES (_VCMP_CTRL_WARMTIME_64CYCLES << 8) /**< Shifted mode 64CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_128CYCLES (_VCMP_CTRL_WARMTIME_128CYCLES << 8) /**< Shifted mode 128CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_256CYCLES (_VCMP_CTRL_WARMTIME_256CYCLES << 8) /**< Shifted mode 256CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_WARMTIME_512CYCLES (_VCMP_CTRL_WARMTIME_512CYCLES << 8) /**< Shifted mode 512CYCLES for VCMP_CTRL */
-#define VCMP_CTRL_IRISE (0x1UL << 16) /**< Rising Edge Interrupt Sense */
-#define _VCMP_CTRL_IRISE_SHIFT 16 /**< Shift value for VCMP_IRISE */
-#define _VCMP_CTRL_IRISE_MASK 0x10000UL /**< Bit mask for VCMP_IRISE */
-#define _VCMP_CTRL_IRISE_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_IRISE_DEFAULT (_VCMP_CTRL_IRISE_DEFAULT << 16) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_IFALL (0x1UL << 17) /**< Falling Edge Interrupt Sense */
-#define _VCMP_CTRL_IFALL_SHIFT 17 /**< Shift value for VCMP_IFALL */
-#define _VCMP_CTRL_IFALL_MASK 0x20000UL /**< Bit mask for VCMP_IFALL */
-#define _VCMP_CTRL_IFALL_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_IFALL_DEFAULT (_VCMP_CTRL_IFALL_DEFAULT << 17) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define _VCMP_CTRL_BIASPROG_SHIFT 24 /**< Shift value for VCMP_BIASPROG */
-#define _VCMP_CTRL_BIASPROG_MASK 0xF000000UL /**< Bit mask for VCMP_BIASPROG */
-#define _VCMP_CTRL_BIASPROG_DEFAULT 0x00000007UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_BIASPROG_DEFAULT (_VCMP_CTRL_BIASPROG_DEFAULT << 24) /**< Shifted mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_HALFBIAS (0x1UL << 30) /**< Half Bias Current */
-#define _VCMP_CTRL_HALFBIAS_SHIFT 30 /**< Shift value for VCMP_HALFBIAS */
-#define _VCMP_CTRL_HALFBIAS_MASK 0x40000000UL /**< Bit mask for VCMP_HALFBIAS */
-#define _VCMP_CTRL_HALFBIAS_DEFAULT 0x00000001UL /**< Mode DEFAULT for VCMP_CTRL */
-#define VCMP_CTRL_HALFBIAS_DEFAULT (_VCMP_CTRL_HALFBIAS_DEFAULT << 30) /**< Shifted mode DEFAULT for VCMP_CTRL */
-
-/* Bit fields for VCMP INPUTSEL */
-#define _VCMP_INPUTSEL_RESETVALUE 0x00000000UL /**< Default value for VCMP_INPUTSEL */
-#define _VCMP_INPUTSEL_MASK 0x0000013FUL /**< Mask for VCMP_INPUTSEL */
-#define _VCMP_INPUTSEL_TRIGLEVEL_SHIFT 0 /**< Shift value for VCMP_TRIGLEVEL */
-#define _VCMP_INPUTSEL_TRIGLEVEL_MASK 0x3FUL /**< Bit mask for VCMP_TRIGLEVEL */
-#define _VCMP_INPUTSEL_TRIGLEVEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_INPUTSEL */
-#define VCMP_INPUTSEL_TRIGLEVEL_DEFAULT (_VCMP_INPUTSEL_TRIGLEVEL_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_INPUTSEL */
-#define VCMP_INPUTSEL_LPREF (0x1UL << 8) /**< Low Power Reference */
-#define _VCMP_INPUTSEL_LPREF_SHIFT 8 /**< Shift value for VCMP_LPREF */
-#define _VCMP_INPUTSEL_LPREF_MASK 0x100UL /**< Bit mask for VCMP_LPREF */
-#define _VCMP_INPUTSEL_LPREF_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_INPUTSEL */
-#define VCMP_INPUTSEL_LPREF_DEFAULT (_VCMP_INPUTSEL_LPREF_DEFAULT << 8) /**< Shifted mode DEFAULT for VCMP_INPUTSEL */
-
-/* Bit fields for VCMP STATUS */
-#define _VCMP_STATUS_RESETVALUE 0x00000000UL /**< Default value for VCMP_STATUS */
-#define _VCMP_STATUS_MASK 0x00000003UL /**< Mask for VCMP_STATUS */
-#define VCMP_STATUS_VCMPACT (0x1UL << 0) /**< Voltage Supply Comparator Active */
-#define _VCMP_STATUS_VCMPACT_SHIFT 0 /**< Shift value for VCMP_VCMPACT */
-#define _VCMP_STATUS_VCMPACT_MASK 0x1UL /**< Bit mask for VCMP_VCMPACT */
-#define _VCMP_STATUS_VCMPACT_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_STATUS */
-#define VCMP_STATUS_VCMPACT_DEFAULT (_VCMP_STATUS_VCMPACT_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_STATUS */
-#define VCMP_STATUS_VCMPOUT (0x1UL << 1) /**< Voltage Supply Comparator Output */
-#define _VCMP_STATUS_VCMPOUT_SHIFT 1 /**< Shift value for VCMP_VCMPOUT */
-#define _VCMP_STATUS_VCMPOUT_MASK 0x2UL /**< Bit mask for VCMP_VCMPOUT */
-#define _VCMP_STATUS_VCMPOUT_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_STATUS */
-#define VCMP_STATUS_VCMPOUT_DEFAULT (_VCMP_STATUS_VCMPOUT_DEFAULT << 1) /**< Shifted mode DEFAULT for VCMP_STATUS */
-
-/* Bit fields for VCMP IEN */
-#define _VCMP_IEN_RESETVALUE 0x00000000UL /**< Default value for VCMP_IEN */
-#define _VCMP_IEN_MASK 0x00000003UL /**< Mask for VCMP_IEN */
-#define VCMP_IEN_EDGE (0x1UL << 0) /**< Edge Trigger Interrupt Enable */
-#define _VCMP_IEN_EDGE_SHIFT 0 /**< Shift value for VCMP_EDGE */
-#define _VCMP_IEN_EDGE_MASK 0x1UL /**< Bit mask for VCMP_EDGE */
-#define _VCMP_IEN_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IEN */
-#define VCMP_IEN_EDGE_DEFAULT (_VCMP_IEN_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_IEN */
-#define VCMP_IEN_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Enable */
-#define _VCMP_IEN_WARMUP_SHIFT 1 /**< Shift value for VCMP_WARMUP */
-#define _VCMP_IEN_WARMUP_MASK 0x2UL /**< Bit mask for VCMP_WARMUP */
-#define _VCMP_IEN_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IEN */
-#define VCMP_IEN_WARMUP_DEFAULT (_VCMP_IEN_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for VCMP_IEN */
-
-/* Bit fields for VCMP IF */
-#define _VCMP_IF_RESETVALUE 0x00000000UL /**< Default value for VCMP_IF */
-#define _VCMP_IF_MASK 0x00000003UL /**< Mask for VCMP_IF */
-#define VCMP_IF_EDGE (0x1UL << 0) /**< Edge Triggered Interrupt Flag */
-#define _VCMP_IF_EDGE_SHIFT 0 /**< Shift value for VCMP_EDGE */
-#define _VCMP_IF_EDGE_MASK 0x1UL /**< Bit mask for VCMP_EDGE */
-#define _VCMP_IF_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IF */
-#define VCMP_IF_EDGE_DEFAULT (_VCMP_IF_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_IF */
-#define VCMP_IF_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Flag */
-#define _VCMP_IF_WARMUP_SHIFT 1 /**< Shift value for VCMP_WARMUP */
-#define _VCMP_IF_WARMUP_MASK 0x2UL /**< Bit mask for VCMP_WARMUP */
-#define _VCMP_IF_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IF */
-#define VCMP_IF_WARMUP_DEFAULT (_VCMP_IF_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for VCMP_IF */
-
-/* Bit fields for VCMP IFS */
-#define _VCMP_IFS_RESETVALUE 0x00000000UL /**< Default value for VCMP_IFS */
-#define _VCMP_IFS_MASK 0x00000003UL /**< Mask for VCMP_IFS */
-#define VCMP_IFS_EDGE (0x1UL << 0) /**< Edge Triggered Interrupt Flag Set */
-#define _VCMP_IFS_EDGE_SHIFT 0 /**< Shift value for VCMP_EDGE */
-#define _VCMP_IFS_EDGE_MASK 0x1UL /**< Bit mask for VCMP_EDGE */
-#define _VCMP_IFS_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IFS */
-#define VCMP_IFS_EDGE_DEFAULT (_VCMP_IFS_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_IFS */
-#define VCMP_IFS_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Flag Set */
-#define _VCMP_IFS_WARMUP_SHIFT 1 /**< Shift value for VCMP_WARMUP */
-#define _VCMP_IFS_WARMUP_MASK 0x2UL /**< Bit mask for VCMP_WARMUP */
-#define _VCMP_IFS_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IFS */
-#define VCMP_IFS_WARMUP_DEFAULT (_VCMP_IFS_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for VCMP_IFS */
-
-/* Bit fields for VCMP IFC */
-#define _VCMP_IFC_RESETVALUE 0x00000000UL /**< Default value for VCMP_IFC */
-#define _VCMP_IFC_MASK 0x00000003UL /**< Mask for VCMP_IFC */
-#define VCMP_IFC_EDGE (0x1UL << 0) /**< Edge Triggered Interrupt Flag Clear */
-#define _VCMP_IFC_EDGE_SHIFT 0 /**< Shift value for VCMP_EDGE */
-#define _VCMP_IFC_EDGE_MASK 0x1UL /**< Bit mask for VCMP_EDGE */
-#define _VCMP_IFC_EDGE_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IFC */
-#define VCMP_IFC_EDGE_DEFAULT (_VCMP_IFC_EDGE_DEFAULT << 0) /**< Shifted mode DEFAULT for VCMP_IFC */
-#define VCMP_IFC_WARMUP (0x1UL << 1) /**< Warm-up Interrupt Flag Clear */
-#define _VCMP_IFC_WARMUP_SHIFT 1 /**< Shift value for VCMP_WARMUP */
-#define _VCMP_IFC_WARMUP_MASK 0x2UL /**< Bit mask for VCMP_WARMUP */
-#define _VCMP_IFC_WARMUP_DEFAULT 0x00000000UL /**< Mode DEFAULT for VCMP_IFC */
-#define VCMP_IFC_WARMUP_DEFAULT (_VCMP_IFC_WARMUP_DEFAULT << 1) /**< Shifted mode DEFAULT for VCMP_IFC */
-
-/** @} End of group EFM32ZG_VCMP */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_wdog.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_wdog.h
deleted file mode 100644
index a7cd51000f..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/efm32zg_wdog.h
+++ /dev/null
@@ -1,139 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief EFM32ZG_WDOG register and bit field definitions
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#if defined(__ICCARM__)
-#pragma system_include /* Treat file as system include file. */
-#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
-#pragma clang system_header /* Treat file as system include file. */
-#endif
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @defgroup EFM32ZG_WDOG
- * @{
- * @brief EFM32ZG_WDOG Register Declaration
- ******************************************************************************/
-typedef struct {
- __IOM uint32_t CTRL; /**< Control Register */
- __IOM uint32_t CMD; /**< Command Register */
-
- __IM uint32_t SYNCBUSY; /**< Synchronization Busy Register */
-} WDOG_TypeDef; /** WDOG Register Declaration *//** @} */
-
-/***************************************************************************//**
- * @defgroup EFM32ZG_WDOG_BitFields
- * @{
- ******************************************************************************/
-
-/* Bit fields for WDOG CTRL */
-#define _WDOG_CTRL_RESETVALUE 0x00000F00UL /**< Default value for WDOG_CTRL */
-#define _WDOG_CTRL_MASK 0x00003F7FUL /**< Mask for WDOG_CTRL */
-#define WDOG_CTRL_EN (0x1UL << 0) /**< Watchdog Timer Enable */
-#define _WDOG_CTRL_EN_SHIFT 0 /**< Shift value for WDOG_EN */
-#define _WDOG_CTRL_EN_MASK 0x1UL /**< Bit mask for WDOG_EN */
-#define _WDOG_CTRL_EN_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EN_DEFAULT (_WDOG_CTRL_EN_DEFAULT << 0) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_DEBUGRUN (0x1UL << 1) /**< Debug Mode Run Enable */
-#define _WDOG_CTRL_DEBUGRUN_SHIFT 1 /**< Shift value for WDOG_DEBUGRUN */
-#define _WDOG_CTRL_DEBUGRUN_MASK 0x2UL /**< Bit mask for WDOG_DEBUGRUN */
-#define _WDOG_CTRL_DEBUGRUN_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_DEBUGRUN_DEFAULT (_WDOG_CTRL_DEBUGRUN_DEFAULT << 1) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EM2RUN (0x1UL << 2) /**< Energy Mode 2 Run Enable */
-#define _WDOG_CTRL_EM2RUN_SHIFT 2 /**< Shift value for WDOG_EM2RUN */
-#define _WDOG_CTRL_EM2RUN_MASK 0x4UL /**< Bit mask for WDOG_EM2RUN */
-#define _WDOG_CTRL_EM2RUN_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EM2RUN_DEFAULT (_WDOG_CTRL_EM2RUN_DEFAULT << 2) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EM3RUN (0x1UL << 3) /**< Energy Mode 3 Run Enable */
-#define _WDOG_CTRL_EM3RUN_SHIFT 3 /**< Shift value for WDOG_EM3RUN */
-#define _WDOG_CTRL_EM3RUN_MASK 0x8UL /**< Bit mask for WDOG_EM3RUN */
-#define _WDOG_CTRL_EM3RUN_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EM3RUN_DEFAULT (_WDOG_CTRL_EM3RUN_DEFAULT << 3) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_LOCK (0x1UL << 4) /**< Configuration lock */
-#define _WDOG_CTRL_LOCK_SHIFT 4 /**< Shift value for WDOG_LOCK */
-#define _WDOG_CTRL_LOCK_MASK 0x10UL /**< Bit mask for WDOG_LOCK */
-#define _WDOG_CTRL_LOCK_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_LOCK_DEFAULT (_WDOG_CTRL_LOCK_DEFAULT << 4) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EM4BLOCK (0x1UL << 5) /**< Energy Mode 4 Block */
-#define _WDOG_CTRL_EM4BLOCK_SHIFT 5 /**< Shift value for WDOG_EM4BLOCK */
-#define _WDOG_CTRL_EM4BLOCK_MASK 0x20UL /**< Bit mask for WDOG_EM4BLOCK */
-#define _WDOG_CTRL_EM4BLOCK_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_EM4BLOCK_DEFAULT (_WDOG_CTRL_EM4BLOCK_DEFAULT << 5) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_SWOSCBLOCK (0x1UL << 6) /**< Software Oscillator Disable Block */
-#define _WDOG_CTRL_SWOSCBLOCK_SHIFT 6 /**< Shift value for WDOG_SWOSCBLOCK */
-#define _WDOG_CTRL_SWOSCBLOCK_MASK 0x40UL /**< Bit mask for WDOG_SWOSCBLOCK */
-#define _WDOG_CTRL_SWOSCBLOCK_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_SWOSCBLOCK_DEFAULT (_WDOG_CTRL_SWOSCBLOCK_DEFAULT << 6) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define _WDOG_CTRL_PERSEL_SHIFT 8 /**< Shift value for WDOG_PERSEL */
-#define _WDOG_CTRL_PERSEL_MASK 0xF00UL /**< Bit mask for WDOG_PERSEL */
-#define _WDOG_CTRL_PERSEL_DEFAULT 0x0000000FUL /**< Mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_PERSEL_DEFAULT (_WDOG_CTRL_PERSEL_DEFAULT << 8) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define _WDOG_CTRL_CLKSEL_SHIFT 12 /**< Shift value for WDOG_CLKSEL */
-#define _WDOG_CTRL_CLKSEL_MASK 0x3000UL /**< Bit mask for WDOG_CLKSEL */
-#define _WDOG_CTRL_CLKSEL_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CTRL */
-#define _WDOG_CTRL_CLKSEL_ULFRCO 0x00000000UL /**< Mode ULFRCO for WDOG_CTRL */
-#define _WDOG_CTRL_CLKSEL_LFRCO 0x00000001UL /**< Mode LFRCO for WDOG_CTRL */
-#define _WDOG_CTRL_CLKSEL_LFXO 0x00000002UL /**< Mode LFXO for WDOG_CTRL */
-#define WDOG_CTRL_CLKSEL_DEFAULT (_WDOG_CTRL_CLKSEL_DEFAULT << 12) /**< Shifted mode DEFAULT for WDOG_CTRL */
-#define WDOG_CTRL_CLKSEL_ULFRCO (_WDOG_CTRL_CLKSEL_ULFRCO << 12) /**< Shifted mode ULFRCO for WDOG_CTRL */
-#define WDOG_CTRL_CLKSEL_LFRCO (_WDOG_CTRL_CLKSEL_LFRCO << 12) /**< Shifted mode LFRCO for WDOG_CTRL */
-#define WDOG_CTRL_CLKSEL_LFXO (_WDOG_CTRL_CLKSEL_LFXO << 12) /**< Shifted mode LFXO for WDOG_CTRL */
-
-/* Bit fields for WDOG CMD */
-#define _WDOG_CMD_RESETVALUE 0x00000000UL /**< Default value for WDOG_CMD */
-#define _WDOG_CMD_MASK 0x00000001UL /**< Mask for WDOG_CMD */
-#define WDOG_CMD_CLEAR (0x1UL << 0) /**< Watchdog Timer Clear */
-#define _WDOG_CMD_CLEAR_SHIFT 0 /**< Shift value for WDOG_CLEAR */
-#define _WDOG_CMD_CLEAR_MASK 0x1UL /**< Bit mask for WDOG_CLEAR */
-#define _WDOG_CMD_CLEAR_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_CMD */
-#define _WDOG_CMD_CLEAR_UNCHANGED 0x00000000UL /**< Mode UNCHANGED for WDOG_CMD */
-#define _WDOG_CMD_CLEAR_CLEARED 0x00000001UL /**< Mode CLEARED for WDOG_CMD */
-#define WDOG_CMD_CLEAR_DEFAULT (_WDOG_CMD_CLEAR_DEFAULT << 0) /**< Shifted mode DEFAULT for WDOG_CMD */
-#define WDOG_CMD_CLEAR_UNCHANGED (_WDOG_CMD_CLEAR_UNCHANGED << 0) /**< Shifted mode UNCHANGED for WDOG_CMD */
-#define WDOG_CMD_CLEAR_CLEARED (_WDOG_CMD_CLEAR_CLEARED << 0) /**< Shifted mode CLEARED for WDOG_CMD */
-
-/* Bit fields for WDOG SYNCBUSY */
-#define _WDOG_SYNCBUSY_RESETVALUE 0x00000000UL /**< Default value for WDOG_SYNCBUSY */
-#define _WDOG_SYNCBUSY_MASK 0x00000003UL /**< Mask for WDOG_SYNCBUSY */
-#define WDOG_SYNCBUSY_CTRL (0x1UL << 0) /**< CTRL Register Busy */
-#define _WDOG_SYNCBUSY_CTRL_SHIFT 0 /**< Shift value for WDOG_CTRL */
-#define _WDOG_SYNCBUSY_CTRL_MASK 0x1UL /**< Bit mask for WDOG_CTRL */
-#define _WDOG_SYNCBUSY_CTRL_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_SYNCBUSY */
-#define WDOG_SYNCBUSY_CTRL_DEFAULT (_WDOG_SYNCBUSY_CTRL_DEFAULT << 0) /**< Shifted mode DEFAULT for WDOG_SYNCBUSY */
-#define WDOG_SYNCBUSY_CMD (0x1UL << 1) /**< CMD Register Busy */
-#define _WDOG_SYNCBUSY_CMD_SHIFT 1 /**< Shift value for WDOG_CMD */
-#define _WDOG_SYNCBUSY_CMD_MASK 0x2UL /**< Bit mask for WDOG_CMD */
-#define _WDOG_SYNCBUSY_CMD_DEFAULT 0x00000000UL /**< Mode DEFAULT for WDOG_SYNCBUSY */
-#define WDOG_SYNCBUSY_CMD_DEFAULT (_WDOG_SYNCBUSY_CMD_DEFAULT << 1) /**< Shifted mode DEFAULT for WDOG_SYNCBUSY */
-
-/** @} End of group EFM32ZG_WDOG */
-/** @} End of group Parts */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/em_device.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/em_device.h
deleted file mode 100644
index b89df7d232..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/em_device.h
+++ /dev/null
@@ -1,95 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M Peripheral Access Layer for Silicon Laboratories
- * microcontroller devices
- *
- * This is a convenience header file for defining the part number on the
- * build command line, instead of specifying the part specific header file.
- *
- * @verbatim
- * Example: Add "-DEFM32G890F128" to your build options, to define part
- * Add "#include "em_device.h" to your source files
- * @endverbatim
- *
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#ifndef EM_DEVICE_H
-#define EM_DEVICE_H
-
-#if defined(EFM32ZG108F16)
-#include "efm32zg108f16.h"
-
-#elif defined(EFM32ZG108F32)
-#include "efm32zg108f32.h"
-
-#elif defined(EFM32ZG108F4)
-#include "efm32zg108f4.h"
-
-#elif defined(EFM32ZG108F8)
-#include "efm32zg108f8.h"
-
-#elif defined(EFM32ZG110F16)
-#include "efm32zg110f16.h"
-
-#elif defined(EFM32ZG110F32)
-#include "efm32zg110f32.h"
-
-#elif defined(EFM32ZG110F4)
-#include "efm32zg110f4.h"
-
-#elif defined(EFM32ZG110F8)
-#include "efm32zg110f8.h"
-
-#elif defined(EFM32ZG210F16)
-#include "efm32zg210f16.h"
-
-#elif defined(EFM32ZG210F32)
-#include "efm32zg210f32.h"
-
-#elif defined(EFM32ZG210F4)
-#include "efm32zg210f4.h"
-
-#elif defined(EFM32ZG210F8)
-#include "efm32zg210f8.h"
-
-#elif defined(EFM32ZG222F16)
-#include "efm32zg222f16.h"
-
-#elif defined(EFM32ZG222F32)
-#include "efm32zg222f32.h"
-
-#elif defined(EFM32ZG222F4)
-#include "efm32zg222f4.h"
-
-#elif defined(EFM32ZG222F8)
-#include "efm32zg222f8.h"
-
-#else
-#error "em_device.h: PART NUMBER undefined"
-#endif
-#endif /* EM_DEVICE_H */
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/system_efm32zg.c b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/system_efm32zg.c
deleted file mode 100644
index 056f32d087..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/system_efm32zg.c
+++ /dev/null
@@ -1,383 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M0+ System Layer for EFM32ZG devices.
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#include
-#include "em_device.h"
-
-/*******************************************************************************
- ****************************** DEFINES ************************************
- ******************************************************************************/
-
-/** LFRCO frequency, tuned to below frequency during manufacturing. */
-#define EFM32_LFRCO_FREQ (32768UL)
-/** ULFRCO frequency. */
-#define EFM32_ULFRCO_FREQ (1000UL)
-
-#if defined(__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
-#if defined(__ICCARM__) /* IAR requires the __vector_table symbol */
-#define __Vectors __vector_table
-#endif
-extern const tVectorEntry __Vectors[];
-#endif
-
-/*******************************************************************************
- ************************** LOCAL VARIABLES ********************************
- ******************************************************************************/
-
-/* System oscillator frequencies. These frequencies are normally constant */
-/* for a target, but they are made configurable in order to allow run-time */
-/* handling of different boards. The crystal oscillator clocks can be set */
-/* compile time to a non-default value by defining respective EFM32_nFXO_FREQ */
-/* values according to board design. By defining the EFM32_nFXO_FREQ to 0, */
-/* one indicates that the oscillator is not present, in order to save some */
-/* SW footprint. */
-
-#ifndef EFM32_HFXO_FREQ
-/** HFXO frequency. */
-#define EFM32_HFXO_FREQ (24000000UL)
-#endif
-
-/** Maximum HFRCO frequency. */
-#define EFM32_HFRCO_MAX_FREQ (21000000UL)
-
-/* Do not define variable if HF crystal oscillator not present */
-#if (EFM32_HFXO_FREQ > 0U)
-/** @cond DO_NOT_INCLUDE_WITH_DOXYGEN */
-/** System HFXO clock. */
-static uint32_t SystemHFXOClock = EFM32_HFXO_FREQ;
-/** @endcond (DO_NOT_INCLUDE_WITH_DOXYGEN) */
-#endif
-
-#ifndef EFM32_LFXO_FREQ
-/** LFXO frequency. */
-#define EFM32_LFXO_FREQ (EFM32_LFRCO_FREQ)
-#endif
-
-/* Do not define variable if LF crystal oscillator not present */
-#if (EFM32_LFXO_FREQ > 0U)
-/** @cond DO_NOT_INCLUDE_WITH_DOXYGEN */
-/** System LFXO clock. */
-static uint32_t SystemLFXOClock = EFM32_LFXO_FREQ;
-/** @endcond (DO_NOT_INCLUDE_WITH_DOXYGEN) */
-#endif
-
-/*******************************************************************************
- ************************** GLOBAL VARIABLES *******************************
- ******************************************************************************/
-
-/**
- * @brief
- * System System Clock Frequency (Core Clock).
- *
- * @details
- * Required CMSIS global variable that must be kept up-to-date.
- */
-uint32_t SystemCoreClock = 14000000UL;
-
-/*******************************************************************************
- ************************** GLOBAL FUNCTIONS *******************************
- ******************************************************************************/
-
-/***************************************************************************//**
- * @brief
- * Get the current core clock frequency.
- *
- * @details
- * Calculate and get the current core clock frequency based on the current
- * configuration. Assuming that the SystemCoreClock global variable is
- * maintained, the core clock frequency is stored in that variable as well.
- * This function will however calculate the core clock based on actual HW
- * configuration. It will also update the SystemCoreClock global variable.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * The current core clock frequency in Hz.
- ******************************************************************************/
-uint32_t SystemCoreClockGet(void)
-{
- uint32_t ret;
-
- ret = SystemHFClockGet();
- ret >>= (CMU->HFCORECLKDIV & _CMU_HFCORECLKDIV_HFCORECLKDIV_MASK)
- >> _CMU_HFCORECLKDIV_HFCORECLKDIV_SHIFT;
-
- /* Keep CMSIS variable up-to-date just in case */
- SystemCoreClock = ret;
-
- return ret;
-}
-
-/***************************************************************************//**
- * @brief
- * Get the maximum core clock frequency.
- *
- * @note
- * This is an EFR32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * The maximum core clock frequency in Hz.
- ******************************************************************************/
-uint32_t SystemMaxCoreClockGet(void)
-{
-#if (EFM32_HFRCO_MAX_FREQ > EFM32_HFXO_FREQ)
- return EFM32_HFRCO_MAX_FREQ;
-#else
- return EFM32_HFXO_FREQ;
-#endif
-}
-
-/***************************************************************************//**
- * @brief
- * Get the current HFCLK frequency.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * The current HFCLK frequency in Hz.
- ******************************************************************************/
-uint32_t SystemHFClockGet(void)
-{
- uint32_t ret;
-
- switch (CMU->STATUS & (CMU_STATUS_HFRCOSEL | CMU_STATUS_HFXOSEL
- | CMU_STATUS_LFRCOSEL | CMU_STATUS_LFXOSEL)) {
- case CMU_STATUS_LFXOSEL:
-#if (EFM32_LFXO_FREQ > 0U)
- ret = SystemLFXOClock;
-#else
- /* We should not get here, since core should not be clocked. May */
- /* be caused by a misconfiguration though. */
- ret = 0U;
-#endif
- break;
-
- case CMU_STATUS_LFRCOSEL:
- ret = EFM32_LFRCO_FREQ;
- break;
-
- case CMU_STATUS_HFXOSEL:
-#if (EFM32_HFXO_FREQ > 0U)
- ret = SystemHFXOClock;
-#else
- /* We should not get here, since core should not be clocked. May */
- /* be caused by a misconfiguration though. */
- ret = 0U;
-#endif
- break;
-
- default: /* CMU_STATUS_HFRCOSEL */
- switch (CMU->HFRCOCTRL & _CMU_HFRCOCTRL_BAND_MASK) {
- case CMU_HFRCOCTRL_BAND_21MHZ:
- ret = 21000000U;
- break;
-
- case CMU_HFRCOCTRL_BAND_14MHZ:
- ret = 14000000U;
- break;
-
- case CMU_HFRCOCTRL_BAND_11MHZ:
- ret = 11000000U;
- break;
-
- case CMU_HFRCOCTRL_BAND_7MHZ:
- ret = 6600000U;
- break;
-
- case CMU_HFRCOCTRL_BAND_1MHZ:
- ret = 1200000U;
- break;
-
- default:
- ret = 0U;
- break;
- }
- break;
- }
-
- return ret;
-}
-
-/***************************************************************************//**
- * @brief
- * Get high frequency crystal oscillator clock frequency for target system.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * HFXO frequency in Hz.
- ******************************************************************************/
-uint32_t SystemHFXOClockGet(void)
-{
- /* External crystal oscillator present? */
-#if (EFM32_HFXO_FREQ > 0U)
- return SystemHFXOClock;
-#else
- return 0U;
-#endif
-}
-
-/***************************************************************************//**
- * @brief
- * Set high frequency crystal oscillator clock frequency for target system.
- *
- * @note
- * This function is mainly provided for being able to handle target systems
- * with different HF crystal oscillator frequencies run-time. If used, it
- * should probably only be used once during system startup.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @param[in] freq
- * HFXO frequency in Hz used for target.
- ******************************************************************************/
-void SystemHFXOClockSet(uint32_t freq)
-{
- /* External crystal oscillator present? */
-#if (EFM32_HFXO_FREQ > 0U)
- SystemHFXOClock = freq;
-
- /* Update core clock frequency if HFXO is used to clock core */
- if ((CMU->STATUS & CMU_STATUS_HFXOSEL) != 0U) {
- /* The function will update the global variable */
- (void)SystemCoreClockGet();
- }
-#else
- (void)freq; /* Unused parameter */
-#endif
-}
-
-/***************************************************************************//**
- * @brief
- * Initialize the system.
- *
- * @details
- * Do required generic HW system init.
- *
- * @note
- * This function is invoked during system init, before the main() routine
- * and any data has been initialized. For this reason, it cannot do any
- * initialization of variables etc.
- ******************************************************************************/
-void SystemInit(void)
-{
-#if defined(__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
- SCB->VTOR = (uint32_t)&__Vectors;
-#endif
-}
-
-/***************************************************************************//**
- * @brief
- * Get low frequency RC oscillator clock frequency for target system.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * LFRCO frequency in Hz.
- ******************************************************************************/
-uint32_t SystemLFRCOClockGet(void)
-{
- /* Currently we assume that this frequency is properly tuned during */
- /* manufacturing and is not changed after reset. If future requirements */
- /* for re-tuning by user, we can add support for that. */
- return EFM32_LFRCO_FREQ;
-}
-
-/***************************************************************************//**
- * @brief
- * Get ultra low frequency RC oscillator clock frequency for target system.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * ULFRCO frequency in Hz.
- ******************************************************************************/
-uint32_t SystemULFRCOClockGet(void)
-{
- /* The ULFRCO frequency is not tuned, and can be very inaccurate */
- return EFM32_ULFRCO_FREQ;
-}
-
-/***************************************************************************//**
- * @brief
- * Get low frequency crystal oscillator clock frequency for target system.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @return
- * LFXO frequency in Hz.
- ******************************************************************************/
-uint32_t SystemLFXOClockGet(void)
-{
- /* External crystal oscillator present? */
-#if (EFM32_LFXO_FREQ > 0U)
- return SystemLFXOClock;
-#else
- return 0U;
-#endif
-}
-
-/***************************************************************************//**
- * @brief
- * Set low frequency crystal oscillator clock frequency for target system.
- *
- * @note
- * This function is mainly provided for being able to handle target systems
- * with different HF crystal oscillator frequencies run-time. If used, it
- * should probably only be used once during system startup.
- *
- * @note
- * This is an EFM32 proprietary function, not part of the CMSIS definition.
- *
- * @param[in] freq
- * LFXO frequency in Hz used for target.
- ******************************************************************************/
-void SystemLFXOClockSet(uint32_t freq)
-{
- /* External crystal oscillator present? */
-#if (EFM32_LFXO_FREQ > 0U)
- SystemLFXOClock = freq;
-
- /* Update core clock frequency if LFXO is used to clock core */
- if ((CMU->STATUS & CMU_STATUS_LFXOSEL) != 0U) {
- /* The function will update the global variable */
- (void)SystemCoreClockGet();
- }
-#else
- (void)freq; /* Unused parameter */
-#endif
-}
diff --git a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/system_efm32zg.h b/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/system_efm32zg.h
deleted file mode 100644
index 964086590b..0000000000
--- a/targets/TARGET_Silicon_Labs/TARGET_EFM32/TARGET_EFM32ZG/device/system_efm32zg.h
+++ /dev/null
@@ -1,133 +0,0 @@
-/***************************************************************************//**
- * @file
- * @brief CMSIS Cortex-M System Layer for EFM32 devices.
- *******************************************************************************
- * # License
- * Copyright 2019 Silicon Laboratories Inc. www.silabs.com
- *******************************************************************************
- *
- * SPDX-License-Identifier: Zlib
- *
- * The licensor of this software is Silicon Laboratories Inc.
- *
- * This software is provided 'as-is', without any express or implied
- * warranty. In no event will the authors be held liable for any damages
- * arising from the use of this software.
- *
- * Permission is granted to anyone to use this software for any purpose,
- * including commercial applications, and to alter it and redistribute it
- * freely, subject to the following restrictions:
- *
- * 1. The origin of this software must not be misrepresented; you must not
- * claim that you wrote the original software. If you use this software
- * in a product, an acknowledgment in the product documentation would be
- * appreciated but is not required.
- * 2. Altered source versions must be plainly marked as such, and must not be
- * misrepresented as being the original software.
- * 3. This notice may not be removed or altered from any source distribution.
- *
- ******************************************************************************/
-
-#ifndef SYSTEM_EFM32ZG_H
-#define SYSTEM_EFM32ZG_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#include
-
-/***************************************************************************//**
- * @addtogroup Parts
- * @{
- ******************************************************************************/
-/***************************************************************************//**
- * @addtogroup EFM32ZG EFM32ZG
- * @{
- ******************************************************************************/
-
-/*******************************************************************************
- ****************************** TYPEDEFS ***********************************
- ******************************************************************************/
-
-/* Interrupt vectortable entry */
-typedef union {
- void (*pFunc)(void);
- void *topOfStack;
-} tVectorEntry;
-
-/*******************************************************************************
- ************************** GLOBAL VARIABLES *******************************
- ******************************************************************************/
-
-extern uint32_t SystemCoreClock; /**< System Clock Frequency (Core Clock) */
-
-/*******************************************************************************
- ***************************** PROTOTYPES **********************************
- ******************************************************************************/
-
-/* Interrupt routines - prototypes */
-void Reset_Handler(void); /**< Reset Handler */
-void NMI_Handler(void); /**< NMI Handler */
-void HardFault_Handler(void); /**< Hard Fault Handler */
-void SVC_Handler(void); /**< SVCall Handler */
-void PendSV_Handler(void); /**< PendSV Handler */
-void SysTick_Handler(void); /**< SysTick Handler */
-
-void DMA_IRQHandler(void); /**< DMA IRQ Handler */
-void GPIO_EVEN_IRQHandler(void); /**< GPIO EVEN IRQ Handler */
-void TIMER0_IRQHandler(void); /**< TIMER0 IRQ Handler */
-void ACMP0_IRQHandler(void); /**< ACMP0 IRQ Handler */
-void ADC0_IRQHandler(void); /**< ADC0 IRQ Handler */
-void I2C0_IRQHandler(void); /**< I2C0 IRQ Handler */
-void GPIO_ODD_IRQHandler(void); /**< GPIO ODD IRQ Handler */
-void TIMER1_IRQHandler(void); /**< TIMER1 IRQ Handler */
-void USART1_RX_IRQHandler(void); /**< USART1 RX IRQ Handler */
-void USART1_TX_IRQHandler(void); /**< USART1 TX IRQ Handler */
-void LEUART0_IRQHandler(void); /**< LEUART0 IRQ Handler */
-void PCNT0_IRQHandler(void); /**< PCNT0 IRQ Handler */
-void RTC_IRQHandler(void); /**< RTC IRQ Handler */
-void CMU_IRQHandler(void); /**< CMU IRQ Handler */
-void VCMP_IRQHandler(void); /**< VCMP IRQ Handler */
-void MSC_IRQHandler(void); /**< MSC IRQ Handler */
-void AES_IRQHandler(void); /**< AES IRQ Handler */
-
-uint32_t SystemCoreClockGet(void);
-uint32_t SystemMaxCoreClockGet(void);
-
-/***************************************************************************//**
- * @brief
- * Update CMSIS SystemCoreClock variable.
- *
- * @details
- * CMSIS defines a global variable SystemCoreClock that shall hold the
- * core frequency in Hz. If the core frequency is dynamically changed, the
- * variable must be kept updated in order to be CMSIS compliant.
- *
- * Notice that if only changing core clock frequency through the EFM32 CMU
- * API, this variable will be kept updated. This function is only provided
- * for CMSIS compliance and if a user modifies the the core clock outside
- * the CMU API.
- ******************************************************************************/
-static __INLINE void SystemCoreClockUpdate(void)
-{
- (void)SystemCoreClockGet();
-}
-
-void SystemInit(void);
-uint32_t SystemHFClockGet(void);
-uint32_t SystemHFXOClockGet(void);
-void SystemHFXOClockSet(uint32_t freq);
-uint32_t SystemLFRCOClockGet(void);
-uint32_t SystemULFRCOClockGet(void);
-uint32_t SystemLFXOClockGet(void);
-void SystemLFXOClockSet(uint32_t freq);
-
-/** @} End of group EFM32ZG */
-/** @} End of group Parts */
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* SYSTEM_EFM32ZG_H */
diff --git a/targets/targets.json b/targets/targets.json
index 4d5ad70788..f9d25393f4 100644
--- a/targets/targets.json
+++ b/targets/targets.json
@@ -6958,101 +6958,6 @@
"2015"
]
},
- "EFM32ZG222F32": {
- "inherits": [
- "EFM32"
- ],
- "extra_labels_add": [
- "EFM32ZG",
- "32K",
- "SL_AES"
- ],
- "core": "Cortex-M0+",
- "default_toolchain": "uARM",
- "macros_add": [
- "EFM32ZG222F32",
- "TRANSACTION_QUEUE_SIZE_SPI=0"
- ],
- "supported_toolchains": [
- "GCC_ARM",
- "uARM",
- "IAR"
- ],
- "default_lib": "small",
- "release_versions": [
- "2"
- ],
- "device_name": "EFM32ZG222F32",
- "public": false
- },
- "EFM32ZG_STK3200": {
- "inherits": [
- "EFM32ZG222F32"
- ],
- "device_has": [
- "ANALOGIN",
- "I2C",
- "I2CSLAVE",
- "I2C_ASYNCH",
- "INTERRUPTIN",
- "LPTICKER",
- "PORTIN",
- "PORTINOUT",
- "PORTOUT",
- "PWMOUT",
- "RESET_REASON",
- "SERIAL",
- "SERIAL_ASYNCH",
- "SLEEP",
- "SPI",
- "SPISLAVE",
- "SPI_ASYNCH",
- "STDIO_MESSAGES",
- "USTICKER",
- "WATCHDOG"
- ],
- "forced_reset_timeout": 2,
- "config": {
- "hf_clock_src": {
- "help": "Value: HFXO for external crystal, HFRCO for internal RC oscillator",
- "value": "HFXO",
- "macro_name": "CORE_CLOCK_SOURCE"
- },
- "hfxo_clock_freq": {
- "help": "Value: External crystal frequency in hertz",
- "value": "24000000",
- "macro_name": "HFXO_FREQUENCY"
- },
- "lf_clock_src": {
- "help": "Value: LFXO for external crystal, LFRCO for internal RC oscillator, ULFRCO for internal 1KHz RC oscillator",
- "value": "LFXO",
- "macro_name": "LOW_ENERGY_CLOCK_SOURCE"
- },
- "lfxo_clock_freq": {
- "help": "Value: External crystal frequency in hertz",
- "value": "32768",
- "macro_name": "LFXO_FREQUENCY"
- },
- "hfrco_clock_freq": {
- "help": "Value: Frequency in hertz, must correspond to setting of hfrco_band_select",
- "value": "21000000",
- "macro_name": "HFRCO_FREQUENCY"
- },
- "hfrco_band_select": {
- "help": "Value: One of _CMU_HFRCOCTRL_BAND_21MHZ, _CMU_HFRCOCTRL_BAND_14MHZ, _CMU_HFRCOCTRL_BAND_11MHZ, _CMU_HFRCOCTRL_BAND_7MHZ, _CMU_HFRCOCTRL_BAND_1MHZ. Be sure to set hfrco_clock_freq accordingly!",
- "value": "_CMU_HFRCOCTRL_BAND_21MHZ",
- "macro_name": "HFRCO_FREQUENCY_ENUM"
- },
- "board_controller_enable": {
- "help": "Pin to pull high for enabling the USB serial port",
- "value": "PA9",
- "macro_name": "EFM_BC_EN"
- }
- },
- "detect_code": [
- "2030"
- ]
- },
"EFR32MG1P132F256GM48": {
"inherits": [
"EFM32"