
61 changed files with 23261 additions and 0 deletions
@ -0,0 +1,7 @@
|
||||
# define the module that is build
|
||||
MODULE = cpu
|
||||
|
||||
# add a list of subdirectories, that should also be build
|
||||
DIRS = periph $(RIOTCPU)/cortexm_common
|
||||
|
||||
include $(RIOTBASE)/Makefile.base |
@ -0,0 +1,3 @@
|
||||
export CPU_ARCH = cortex-m4f
|
||||
|
||||
include $(RIOTCPU)/Makefile.include.cortexm_common |
@ -0,0 +1,62 @@
|
||||
/*
|
||||
* Copyright (C) 2015 Freie Universität Berlin |
||||
* |
||||
* This file is subject to the terms and conditions of the GNU Lesser |
||||
* General Public License v2.1. See the file LICENSE in the top level |
||||
* directory for more details. |
||||
*/ |
||||
|
||||
/**
|
||||
* @ingroup cpu_ezr32wg |
||||
* @{ |
||||
* |
||||
* @file |
||||
* @brief Implementation of the CPU initialization |
||||
* |
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de> |
||||
* @} |
||||
*/ |
||||
|
||||
#include "cpu.h" |
||||
#include "periph_conf.h" |
||||
|
||||
/**
|
||||
* @brief Configure clock sources and the CPU frequency |
||||
* |
||||
* On the ezr32wg cpu, we basically have two options for selecting the main |
||||
* clock source, using an external clock source (e.g. a crystal), or using the |
||||
* internal RC oscillator (enabled by default). |
||||
*/ |
||||
static void clk_init(void) |
||||
{ |
||||
/* reset the clock to it's default values */ |
||||
CMU->CTRL = _CMU_CTRL_RESETVALUE; |
||||
|
||||
#ifdef CLOCK_HFXO |
||||
/* configure clock system for external oscillator */ |
||||
#if CLOCK_HFXO > 32000000 |
||||
CMU->CTRL |= CMU_CTRL_HFXOBUFCUR_BOOSTABOVE32MHZ; |
||||
#endif |
||||
/* enable the oscillator */ |
||||
CMU->OSCENCMD = CMU_OSCENCMD_HFXOEN; |
||||
/* wait for external oscillator to be stable */ |
||||
while (!(CMU->STATUS & CMU_STATUS_HFXORDY)); |
||||
/* switch to the external oscillator */ |
||||
CMU->CMD = CMU_CMD_HFCLKSEL_HFXO; |
||||
/* wait until clock source is applied */ |
||||
while (!(CMU->STATUS & CMU_STATUS_HFXOSEL)); |
||||
#endif |
||||
|
||||
/* set the core clock divider */ |
||||
CMU->HFCORECLKDIV = (CLOCK_HFCORECLKDIV - 1); |
||||
/* configure the high speed peripheral clock: set divider and enable it */ |
||||
CMU->HFPERCLKDIV = (CMU_HFPERCLKDIV_HFPERCLKEN | (CLOCK_HFPERCLKDIV - 1)); |
||||
} |
||||
|
||||
void cpu_init(void) |
||||
{ |
||||
/* initialize the Cortex-M core */ |
||||
cortexm_init(); |
||||
/* Initialise clock sources and generic clocks */ |
||||
clk_init(); |
||||
} |
@ -0,0 +1,53 @@
|
||||
/*
|
||||
* Copyright (C) 2015 Freie Universität Berlin |
||||
* |
||||
* This file is subject to the terms and conditions of the GNU Lesser |
||||
* General Public License v2.1. See the file LICENSE in the top level |
||||
* directory for more details. |
||||
*/ |
||||
|
||||
/**
|
||||
* @defgroup cpu_ezr32wg Silicon Labs EZR32WG |
||||
* @ingroup cpu |
||||
* @brief Support for the Silicon Labs EZR32 Wonder Gecko CPU |
||||
* @{ |
||||
* |
||||
* @file |
||||
* @brief Implementation specific CPU configuration options |
||||
* |
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de> |
||||
*/ |
||||
|
||||
#ifndef CPU_CONF_H |
||||
#define CPU_CONF_H |
||||
|
||||
#if (CPU_MODEL == ezr32wg330f256r60) |
||||
#include "ezr32wg330f256r60.h" |
||||
#else |
||||
#error "No CPU headers for the defined CPU_MODEL found" |
||||
#endif |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**
|
||||
* @brief ARM Cortex-M specific CPU configuration |
||||
* @{ |
||||
*/ |
||||
#define CPU_DEFAULT_IRQ_PRIO (1U) |
||||
#define CPU_IRQ_NUMOF (FPUEH_IRQn + 1) |
||||
#define CPU_FLASH_BASE FLASH_BASE |
||||
/** @} */ |
||||
|
||||
/**
|
||||
* @brief CPUID_ID_LEN length of cpuid in bytes |
||||
*/ |
||||
#define CPUID_ID_LEN (8U) /* 64-bit unique ID */ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* __CPU_CONF_H */ |
||||
/** @} */ |
@ -0,0 +1,495 @@
|
||||
/**************************************************************************//**
|
||||
* @file ezr32wg330f256r60.h |
||||
* @brief CMSIS Cortex-M Peripheral Access Layer Header File |
||||
* for EZR32WG330F256R60 |
||||
* @version 4.0.0 |
||||
****************************************************************************** |
||||
* @section License |
||||
* <b>(C) Copyright 2015 Silicon Laboratories, Inc. http://www.silabs.com</b>
|
||||
****************************************************************************** |
||||
* |
||||
* 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.@n |
||||
* 2. Altered source versions must be plainly marked as such, and must not be |
||||
* misrepresented as being the original software.@n |
||||
* 3. This notice may not be removed or altered from any source distribution. |
||||
* |
||||
* DISCLAIMER OF WARRANTY/LIMITATION OF REMEDIES: Silicon Laboratories, Inc. |
||||
* has no obligation to support this Software. Silicon Laboratories, Inc. is |
||||
* providing the Software "AS IS", with no express or implied warranties of any |
||||
* kind, including, but not limited to, any implied warranties of |
||||
* merchantability or fitness for any particular purpose or warranties against |
||||
* infringement of any proprietary rights of a third party. |
||||
* |
||||
* Silicon Laboratories, Inc. will not be liable for any consequential, |
||||
* incidental, or special damages, or any other relief, or for any claim by |
||||
* any third party, arising from your use of this Software. |
||||
* |
||||
*****************************************************************************/ |
||||
|
||||
#ifndef __SILICON_LABS_EZR32WG330F256R60_H__ |
||||
#define __SILICON_LABS_EZR32WG330F256R60_H__ |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/**************************************************************************//**
|
||||
* @addtogroup Parts |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60 EZR32WG330F256R60 |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
/** Interrupt Number Definition */ |
||||
typedef enum IRQn |
||||
{ |
||||
/****** Cortex-M4 Processor Exceptions Numbers *******************************************/ |
||||
NonMaskableInt_IRQn = -14, /*!< 2 Cortex-M4 Non Maskable Interrupt */ |
||||
HardFault_IRQn = -13, /*!< 3 Cortex-M4 Hard Fault Interrupt */ |
||||
MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ |
||||
BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ |
||||
UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ |
||||
SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ |
||||
DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ |
||||
PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ |
||||
SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ |
||||
|
||||
/****** EZR32WG Peripheral Interrupt Numbers *********************************************/ |
||||
DMA_IRQn = 0, /*!< 16+0 EZR32 DMA Interrupt */ |
||||
GPIO_EVEN_IRQn = 1, /*!< 16+1 EZR32 GPIO_EVEN Interrupt */ |
||||
TIMER0_IRQn = 2, /*!< 16+2 EZR32 TIMER0 Interrupt */ |
||||
USARTRF0_RX_IRQn = 3, /*!< 16+3 EZR32 USARTRF0_RX Interrupt */ |
||||
USARTRF0_TX_IRQn = 4, /*!< 16+4 EZR32 USARTRF0_TX Interrupt */ |
||||
USB_IRQn = 5, /*!< 16+5 EZR32 USB Interrupt */ |
||||
ACMP0_IRQn = 6, /*!< 16+6 EZR32 ACMP0 Interrupt */ |
||||
ADC0_IRQn = 7, /*!< 16+7 EZR32 ADC0 Interrupt */ |
||||
DAC0_IRQn = 8, /*!< 16+8 EZR32 DAC0 Interrupt */ |
||||
I2C0_IRQn = 9, /*!< 16+9 EZR32 I2C0 Interrupt */ |
||||
I2C1_IRQn = 10, /*!< 16+10 EZR32 I2C1 Interrupt */ |
||||
GPIO_ODD_IRQn = 11, /*!< 16+11 EZR32 GPIO_ODD Interrupt */ |
||||
TIMER1_IRQn = 12, /*!< 16+12 EZR32 TIMER1 Interrupt */ |
||||
TIMER2_IRQn = 13, /*!< 16+13 EZR32 TIMER2 Interrupt */ |
||||
TIMER3_IRQn = 14, /*!< 16+14 EZR32 TIMER3 Interrupt */ |
||||
USART1_RX_IRQn = 15, /*!< 16+15 EZR32 USART1_RX Interrupt */ |
||||
USART1_TX_IRQn = 16, /*!< 16+16 EZR32 USART1_TX Interrupt */ |
||||
LESENSE_IRQn = 17, /*!< 16+17 EZR32 LESENSE Interrupt */ |
||||
USART2_RX_IRQn = 18, /*!< 16+18 EZR32 USART2_RX Interrupt */ |
||||
USART2_TX_IRQn = 19, /*!< 16+19 EZR32 USART2_TX Interrupt */ |
||||
UART0_RX_IRQn = 20, /*!< 16+20 EZR32 UART0_RX Interrupt */ |
||||
UART0_TX_IRQn = 21, /*!< 16+21 EZR32 UART0_TX Interrupt */ |
||||
UART1_RX_IRQn = 22, /*!< 16+22 EZR32 UART1_RX Interrupt */ |
||||
UART1_TX_IRQn = 23, /*!< 16+23 EZR32 UART1_TX Interrupt */ |
||||
LEUART0_IRQn = 24, /*!< 16+24 EZR32 LEUART0 Interrupt */ |
||||
LEUART1_IRQn = 25, /*!< 16+25 EZR32 LEUART1 Interrupt */ |
||||
LETIMER0_IRQn = 26, /*!< 16+26 EZR32 LETIMER0 Interrupt */ |
||||
PCNT0_IRQn = 27, /*!< 16+27 EZR32 PCNT0 Interrupt */ |
||||
PCNT1_IRQn = 28, /*!< 16+28 EZR32 PCNT1 Interrupt */ |
||||
PCNT2_IRQn = 29, /*!< 16+29 EZR32 PCNT2 Interrupt */ |
||||
RTC_IRQn = 30, /*!< 16+30 EZR32 RTC Interrupt */ |
||||
BURTC_IRQn = 31, /*!< 16+31 EZR32 BURTC Interrupt */ |
||||
CMU_IRQn = 32, /*!< 16+32 EZR32 CMU Interrupt */ |
||||
VCMP_IRQn = 33, /*!< 16+33 EZR32 VCMP Interrupt */ |
||||
MSC_IRQn = 35, /*!< 16+35 EZR32 MSC Interrupt */ |
||||
AES_IRQn = 36, /*!< 16+36 EZR32 AES Interrupt */ |
||||
EMU_IRQn = 38, /*!< 16+38 EZR32 EMU Interrupt */ |
||||
FPUEH_IRQn = 39, /*!< 16+39 EZR32 FPUEH Interrupt */ |
||||
} IRQn_Type; |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_Core EZR32WG330F256R60 Core |
||||
* @{ |
||||
* @brief Processor and Core Peripheral Section |
||||
*****************************************************************************/ |
||||
#define __MPU_PRESENT 1 /**< Presence of MPU */ |
||||
#define __FPU_PRESENT 1 /**< Presence of FPU */ |
||||
#define __NVIC_PRIO_BITS 3 /**< NVIC interrupt priority bits */ |
||||
#define __Vendor_SysTickConfig 0 /**< Is 1 if different SysTick counter is used */ |
||||
|
||||
/** @} End of group EZR32WG330F256R60_Core */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_Part EZR32WG330F256R60 Part |
||||
* @{ |
||||
******************************************************************************/ |
||||
|
||||
/** Part family */ |
||||
#define _EFM32_WONDER_FAMILY 1 /**< Wonder Gecko EFM32WG MCU Family */ |
||||
#define _EFM_DEVICE /**< Silicon Labs EFM-type microcontroller */ |
||||
#define _EZR32_WONDER_FAMILY 1 /**< Wonder Gecko EZR32WG MCU Family */ |
||||
#define _EZR_DEVICE /**< Silicon Labs EZR-type microcontroller */ |
||||
#define _SILICON_LABS_32B_PLATFORM_1 /**< Silicon Labs platform name */ |
||||
#define _SILICON_LABS_32B_PLATFORM 1 /**< Silicon Labs platform name */ |
||||
|
||||
/* If part number is not defined as compiler option, define it */ |
||||
#if !defined(EZR32WG330F256R60) |
||||
#define EZR32WG330F256R60 1 /**< EZR Wonder Gecko Part */ |
||||
#endif |
||||
|
||||
/** Configure part number */ |
||||
#define PART_NUMBER "EZR32WG330F256R60" /**< Part Number */ |
||||
|
||||
/** Memory Base addresses and limits */ |
||||
#define FLASH_MEM_BASE ((uint32_t) 0x0UL) /**< FLASH base address */ |
||||
#define FLASH_MEM_SIZE ((uint32_t) 0x10000000UL) /**< FLASH available address space */ |
||||
#define FLASH_MEM_END ((uint32_t) 0xFFFFFFFUL) /**< FLASH end address */ |
||||
#define FLASH_MEM_BITS ((uint32_t) 0x28UL) /**< FLASH used bits */ |
||||
#define AES_MEM_BASE ((uint32_t) 0x400E0000UL) /**< AES base address */ |
||||
#define AES_MEM_SIZE ((uint32_t) 0x400UL) /**< AES available address space */ |
||||
#define AES_MEM_END ((uint32_t) 0x400E03FFUL) /**< AES end address */ |
||||
#define AES_MEM_BITS ((uint32_t) 0x10UL) /**< AES used bits */ |
||||
#define USBC_MEM_BASE ((uint32_t) 0x40100000UL) /**< USBC base address */ |
||||
#define USBC_MEM_SIZE ((uint32_t) 0x40000UL) /**< USBC available address space */ |
||||
#define USBC_MEM_END ((uint32_t) 0x4013FFFFUL) /**< USBC end address */ |
||||
#define USBC_MEM_BITS ((uint32_t) 0x18UL) /**< USBC used bits */ |
||||
#define PER_MEM_BASE ((uint32_t) 0x40000000UL) /**< PER base address */ |
||||
#define PER_MEM_SIZE ((uint32_t) 0xE0000UL) /**< PER available address space */ |
||||
#define PER_MEM_END ((uint32_t) 0x400DFFFFUL) /**< PER end address */ |
||||
#define PER_MEM_BITS ((uint32_t) 0x20UL) /**< PER used bits */ |
||||
#define RAM_MEM_BASE ((uint32_t) 0x20000000UL) /**< RAM base address */ |
||||
#define RAM_MEM_SIZE ((uint32_t) 0x40000UL) /**< RAM available address space */ |
||||
#define RAM_MEM_END ((uint32_t) 0x2003FFFFUL) /**< RAM end address */ |
||||
#define RAM_MEM_BITS ((uint32_t) 0x18UL) /**< RAM used bits */ |
||||
#define RAM_CODE_MEM_BASE ((uint32_t) 0x10000000UL) /**< RAM_CODE base address */ |
||||
#define RAM_CODE_MEM_SIZE ((uint32_t) 0x20000UL) /**< RAM_CODE available address space */ |
||||
#define RAM_CODE_MEM_END ((uint32_t) 0x1001FFFFUL) /**< RAM_CODE end address */ |
||||
#define RAM_CODE_MEM_BITS ((uint32_t) 0x17UL) /**< RAM_CODE used bits */ |
||||
|
||||
/** Bit banding area */ |
||||
#define BITBAND_PER_BASE ((uint32_t) 0x42000000UL) /**< Peripheral Address Space bit-band area */ |
||||
#define BITBAND_RAM_BASE ((uint32_t) 0x22000000UL) /**< SRAM Address Space bit-band area */ |
||||
|
||||
/** Flash and SRAM limits for EZR32WG330F256R60 */ |
||||
#define FLASH_BASE (0x00000000UL) /**< Flash Base Address */ |
||||
#define FLASH_SIZE (0x00040000UL) /**< Available Flash Memory */ |
||||
#define FLASH_PAGE_SIZE 2048 /**< Flash Memory page size */ |
||||
#define SRAM_BASE (0x20000000UL) /**< SRAM Base Address */ |
||||
#define SRAM_SIZE (0x00008000UL) /**< Available SRAM Memory */ |
||||
#define __CM4_REV 0x001 /**< Cortex-M4 Core revision r0p1 */ |
||||
#define PRS_CHAN_COUNT 12 /**< Number of PRS channels */ |
||||
#define DMA_CHAN_COUNT 12 /**< Number of DMA channels */ |
||||
|
||||
/** AF channels connect the different on-chip peripherals with the af-mux */ |
||||
#define AFCHAN_MAX 84 |
||||
#define AFCHANLOC_MAX 7 |
||||
/** Analog AF channels */ |
||||
#define AFACHAN_MAX 48 |
||||
|
||||
/* Part number capabilities */ |
||||
|
||||
#define USARTRF_PRESENT /**< USARTRF is available in this part */ |
||||
#define USARTRF_COUNT 1 /**< 1 USARTRFs available */ |
||||
#define USART_PRESENT /**< USART is available in this part */ |
||||
#define USART_COUNT 2 /**< 2 USARTs available */ |
||||
#define UART_PRESENT /**< UART is available in this part */ |
||||
#define UART_COUNT 2 /**< 2 UARTs available */ |
||||
#define TIMER_PRESENT /**< TIMER is available in this part */ |
||||
#define TIMER_COUNT 4 /**< 4 TIMERs available */ |
||||
#define ACMP_PRESENT /**< ACMP is available in this part */ |
||||
#define ACMP_COUNT 2 /**< 2 ACMPs available */ |
||||
#define LEUART_PRESENT /**< LEUART is available in this part */ |
||||
#define LEUART_COUNT 2 /**< 2 LEUARTs available */ |
||||
#define LETIMER_PRESENT /**< LETIMER is available in this part */ |
||||
#define LETIMER_COUNT 1 /**< 1 LETIMERs available */ |
||||
#define PCNT_PRESENT /**< PCNT is available in this part */ |
||||
#define PCNT_COUNT 3 /**< 3 PCNTs available */ |
||||
#define I2C_PRESENT /**< I2C is available in this part */ |
||||
#define I2C_COUNT 2 /**< 2 I2Cs available */ |
||||
#define ADC_PRESENT /**< ADC is available in this part */ |
||||
#define ADC_COUNT 1 /**< 1 ADCs available */ |
||||
#define DAC_PRESENT /**< DAC is available in this part */ |
||||
#define DAC_COUNT 1 /**< 1 DACs available */ |
||||
#define DMA_PRESENT |
||||
#define DMA_COUNT 1 |
||||
#define AES_PRESENT |
||||
#define AES_COUNT 1 |
||||
#define USBC_PRESENT |
||||
#define USBC_COUNT 1 |
||||
#define USB_PRESENT |
||||
#define USB_COUNT 1 |
||||
#define LE_PRESENT |
||||
#define LE_COUNT 1 |
||||
#define MSC_PRESENT |
||||
#define MSC_COUNT 1 |
||||
#define EMU_PRESENT |
||||
#define EMU_COUNT 1 |
||||
#define RMU_PRESENT |
||||
#define RMU_COUNT 1 |
||||
#define CMU_PRESENT |
||||
#define CMU_COUNT 1 |
||||
#define LESENSE_PRESENT |
||||
#define LESENSE_COUNT 1 |
||||
#define FPUEH_PRESENT |
||||
#define FPUEH_COUNT 1 |
||||
#define RTC_PRESENT |
||||
#define RTC_COUNT 1 |
||||
#define GPIO_PRESENT |
||||
#define GPIO_COUNT 1 |
||||
#define VCMP_PRESENT |
||||
#define VCMP_COUNT 1 |
||||
#define PRS_PRESENT |
||||
#define PRS_COUNT 1 |
||||
#define BU_PRESENT |
||||
#define BU_COUNT 1 |
||||
#define BURTC_PRESENT |
||||
#define BURTC_COUNT 1 |
||||
#define HFXTAL_PRESENT |
||||
#define HFXTAL_COUNT 1 |
||||
#define LFXTAL_PRESENT |
||||
#define LFXTAL_COUNT 1 |
||||
#define WDOG_PRESENT |
||||
#define WDOG_COUNT 1 |
||||
#define DBG_PRESENT |
||||
#define DBG_COUNT 1 |
||||
#define ETM_PRESENT |
||||
#define ETM_COUNT 1 |
||||
#define BOOTLOADER_PRESENT |
||||
#define BOOTLOADER_COUNT 1 |
||||
#define ANALOG_PRESENT |
||||
#define ANALOG_COUNT 1 |
||||
#define RF_PRESENT |
||||
#define RF_COUNT 1 |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_RF_Interface EZR32WG330F256R60 RF_Interface |
||||
* @brief MCU port/pins used for RF interface. |
||||
* @{ |
||||
*****************************************************************************/ |
||||
#define RF_USARTRF_LOCATION 0 /**< RF SPI-port (USART) location number. */ |
||||
#define RF_USARTRF_CS_PORT 4 /**< Bit banged RF SPI CS GPIO port no. */ |
||||
#define RF_USARTRF_CS_PIN 9 /**< Bit banged RF SPI CS GPIO pin number.*/ |
||||
#define RF_USARTRF_CLK_PORT 4 /**< RF SPI CLK GPIO port number. */ |
||||
#define RF_USARTRF_CLK_PIN 12 /**< RF SPI CLK GPIO pin number. */ |
||||
#define RF_USARTRF_MISO_PORT 4 /**< RF SPI MISO GPIO port number. */ |
||||
#define RF_USARTRF_MISO_PIN 11 /**< RF SPI MISO GPIO pin number. */ |
||||
#define RF_USARTRF_MOSI_PORT 4 /**< RF SPI MOSI GPIO port number. */ |
||||
#define RF_USARTRF_MOSI_PIN 10 /**< RF SPI MOSI GPIO pin number. */ |
||||
#define RF_INT_PORT 4 /**< RF interrupt GPIO port number. */ |
||||
#define RF_INT_PIN 13 /**< RF interrupt GPIO pin number. */ |
||||
#define RF_GPIO0_PORT 0 /**< RF GPIO0 GPIO port number. */ |
||||
#define RF_GPIO0_PIN 15 /**< RF GPIO0 GPIO pin number. */ |
||||
#define RF_GPIO1_PORT 4 /**< RF GPIO1 GPIO port number. */ |
||||
#define RF_GPIO1_PIN 14 /**< RF GPIO1 GPIO pin number. */ |
||||
#define RF_SDN_PORT 4 /**< RF SDN GPIO port number. */ |
||||
#define RF_SDN_PIN 8 /**< RF SDN GPIO pin number. */ |
||||
|
||||
/** @} End of group EZR32WG330F256R60_RF_Interface */ |
||||
|
||||
#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ |
||||
|
||||
/** @} End of group EZR32WG330F256R60_Part */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_Peripheral_TypeDefs EZR32WG330F256R60 Peripheral TypeDefs |
||||
* @{ |
||||
* @brief Device Specific Peripheral Register Structures |
||||
*****************************************************************************/ |
||||
|
||||
#include "ezr32wg_dma_ch.h" |
||||
#include "ezr32wg_dma.h" |
||||
#include "ezr32wg_aes.h" |
||||
#include "ezr32wg_usb_hc.h" |
||||
#include "ezr32wg_usb_diep.h" |
||||
#include "ezr32wg_usb_doep.h" |
||||
#include "ezr32wg_usb.h" |
||||
#include "ezr32wg_msc.h" |
||||
#include "ezr32wg_emu.h" |
||||
#include "ezr32wg_rmu.h" |
||||
#include "ezr32wg_cmu.h" |
||||
#include "ezr32wg_lesense_st.h" |
||||
#include "ezr32wg_lesense_buf.h" |
||||
#include "ezr32wg_lesense_ch.h" |
||||
#include "ezr32wg_lesense.h" |
||||
#include "ezr32wg_fpueh.h" |
||||
#include "ezr32wg_usart.h" |
||||
#include "ezr32wg_timer_cc.h" |
||||
#include "ezr32wg_timer.h" |
||||
#include "ezr32wg_acmp.h" |
||||
#include "ezr32wg_leuart.h" |
||||
#include "ezr32wg_rtc.h" |
||||
#include "ezr32wg_letimer.h" |
||||
#include "ezr32wg_pcnt.h" |
||||
#include "ezr32wg_i2c.h" |
||||
#include "ezr32wg_gpio_p.h" |
||||
#include "ezr32wg_gpio.h" |
||||
#include "ezr32wg_vcmp.h" |
||||
#include "ezr32wg_prs_ch.h" |
||||
#include "ezr32wg_prs.h" |
||||
#include "ezr32wg_adc.h" |
||||
#include "ezr32wg_dac.h" |
||||
#include "ezr32wg_burtc_ret.h" |
||||
#include "ezr32wg_burtc.h" |
||||
#include "ezr32wg_wdog.h" |
||||
#include "ezr32wg_etm.h" |
||||
#include "ezr32wg_dma_descriptor.h" |
||||
#include "ezr32wg_devinfo.h" |
||||
#include "ezr32wg_romtable.h" |
||||
#include "ezr32wg_calibrate.h" |
||||
|
||||
/** @} End of group EZR32WG330F256R60_Peripheral_TypeDefs */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_Peripheral_Base EZR32WG330F256R60 Peripheral Memory Map |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
#define DMA_BASE (0x400C2000UL) /**< DMA base address */ |
||||
#define AES_BASE (0x400E0000UL) /**< AES base address */ |
||||
#define USB_BASE (0x400C4000UL) /**< USB 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 LESENSE_BASE (0x4008C000UL) /**< LESENSE base address */ |
||||
#define FPUEH_BASE (0x400C1C00UL) /**< FPUEH base address */ |
||||
#define USARTRF0_BASE (0x4000C000UL) /**< USARTRF0 base address */ |
||||
#define USART1_BASE (0x4000C400UL) /**< USART1 base address */ |
||||
#define USART2_BASE (0x4000C800UL) /**< USART2 base address */ |
||||
#define UART0_BASE (0x4000E000UL) /**< UART0 base address */ |
||||
#define UART1_BASE (0x4000E400UL) /**< UART1 base address */ |
||||
#define TIMER0_BASE (0x40010000UL) /**< TIMER0 base address */ |
||||
#define TIMER1_BASE (0x40010400UL) /**< TIMER1 base address */ |
||||
#define TIMER2_BASE (0x40010800UL) /**< TIMER2 base address */ |
||||
#define TIMER3_BASE (0x40010C00UL) /**< TIMER3 base address */ |
||||
#define ACMP0_BASE (0x40001000UL) /**< ACMP0 base address */ |
||||
#define ACMP1_BASE (0x40001400UL) /**< ACMP1 base address */ |
||||
#define LEUART0_BASE (0x40084000UL) /**< LEUART0 base address */ |
||||
#define LEUART1_BASE (0x40084400UL) /**< LEUART1 base address */ |
||||
#define RTC_BASE (0x40080000UL) /**< RTC base address */ |
||||
#define LETIMER0_BASE (0x40082000UL) /**< LETIMER0 base address */ |
||||
#define PCNT0_BASE (0x40086000UL) /**< PCNT0 base address */ |
||||
#define PCNT1_BASE (0x40086400UL) /**< PCNT1 base address */ |
||||
#define PCNT2_BASE (0x40086800UL) /**< PCNT2 base address */ |
||||
#define I2C0_BASE (0x4000A000UL) /**< I2C0 base address */ |
||||
#define I2C1_BASE (0x4000A400UL) /**< I2C1 base address */ |
||||
#define GPIO_BASE (0x40006000UL) /**< GPIO base address */ |
||||
#define VCMP_BASE (0x40000000UL) /**< VCMP base address */ |
||||
#define PRS_BASE (0x400CC000UL) /**< PRS base address */ |
||||
#define ADC0_BASE (0x40002000UL) /**< ADC0 base address */ |
||||
#define DAC0_BASE (0x40004000UL) /**< DAC0 base address */ |
||||
#define BURTC_BASE (0x40081000UL) /**< BURTC base address */ |
||||
#define WDOG_BASE (0x40088000UL) /**< WDOG base address */ |
||||
#define ETM_BASE (0xE0041000UL) /**< ETM base address */ |
||||
#define CALIBRATE_BASE (0x0FE08000UL) /**< CALIBRATE base address */ |
||||
#define DEVINFO_BASE (0x0FE081A8UL) /**< DEVINFO base address */ |
||||
#define ROMTABLE_BASE (0xE00FFFD0UL) /**< ROMTABLE base address */ |
||||
#define LOCKBITS_BASE (0x0FE04000UL) /**< Lock-bits page base address */ |
||||
#define USERDATA_BASE (0x0FE00000UL) /**< User data page base address */ |
||||
|
||||
/** @} End of group EZR32WG330F256R60_Peripheral_Base */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_Peripheral_Declaration EZR32WG330F256R60 Peripheral Declarations |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
#define DMA ((DMA_TypeDef *) DMA_BASE) /**< DMA base pointer */ |
||||
#define AES ((AES_TypeDef *) AES_BASE) /**< AES base pointer */ |
||||
#define USB ((USB_TypeDef *) USB_BASE) /**< USB 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 LESENSE ((LESENSE_TypeDef *) LESENSE_BASE) /**< LESENSE base pointer */ |
||||
#define FPUEH ((FPUEH_TypeDef *) FPUEH_BASE) /**< FPUEH base pointer */ |
||||
#define USARTRF0 ((USART_TypeDef *) USARTRF0_BASE) /**< USARTRF0 base pointer */ |
||||
#define USART1 ((USART_TypeDef *) USART1_BASE) /**< USART1 base pointer */ |
||||
#define USART2 ((USART_TypeDef *) USART2_BASE) /**< USART2 base pointer */ |
||||
#define UART0 ((USART_TypeDef *) UART0_BASE) /**< UART0 base pointer */ |
||||
#define UART1 ((USART_TypeDef *) UART1_BASE) /**< UART1 base pointer */ |
||||
#define TIMER0 ((TIMER_TypeDef *) TIMER0_BASE) /**< TIMER0 base pointer */ |
||||
#define TIMER1 ((TIMER_TypeDef *) TIMER1_BASE) /**< TIMER1 base pointer */ |
||||
#define TIMER2 ((TIMER_TypeDef *) TIMER2_BASE) /**< TIMER2 base pointer */ |
||||
#define TIMER3 ((TIMER_TypeDef *) TIMER3_BASE) /**< TIMER3 base pointer */ |
||||
#define ACMP0 ((ACMP_TypeDef *) ACMP0_BASE) /**< ACMP0 base pointer */ |
||||
#define ACMP1 ((ACMP_TypeDef *) ACMP1_BASE) /**< ACMP1 base pointer */ |
||||
#define LEUART0 ((LEUART_TypeDef *) LEUART0_BASE) /**< LEUART0 base pointer */ |
||||
#define LEUART1 ((LEUART_TypeDef *) LEUART1_BASE) /**< LEUART1 base pointer */ |
||||
#define RTC ((RTC_TypeDef *) RTC_BASE) /**< RTC base pointer */ |
||||
#define LETIMER0 ((LETIMER_TypeDef *) LETIMER0_BASE) /**< LETIMER0 base pointer */ |
||||
#define PCNT0 ((PCNT_TypeDef *) PCNT0_BASE) /**< PCNT0 base pointer */ |
||||
#define PCNT1 ((PCNT_TypeDef *) PCNT1_BASE) /**< PCNT1 base pointer */ |
||||
#define PCNT2 ((PCNT_TypeDef *) PCNT2_BASE) /**< PCNT2 base pointer */ |
||||
#define I2C0 ((I2C_TypeDef *) I2C0_BASE) /**< I2C0 base pointer */ |
||||
#define I2C1 ((I2C_TypeDef *) I2C1_BASE) /**< I2C1 base pointer */ |
||||
#define GPIO ((GPIO_TypeDef *) GPIO_BASE) /**< GPIO base pointer */ |
||||
#define VCMP ((VCMP_TypeDef *) VCMP_BASE) /**< VCMP base pointer */ |
||||
#define PRS ((PRS_TypeDef *) PRS_BASE) /**< PRS base pointer */ |
||||
#define ADC0 ((ADC_TypeDef *) ADC0_BASE) /**< ADC0 base pointer */ |
||||
#define DAC0 ((DAC_TypeDef *) DAC0_BASE) /**< DAC0 base pointer */ |
||||
#define BURTC ((BURTC_TypeDef *) BURTC_BASE) /**< BURTC base pointer */ |
||||
#define WDOG ((WDOG_TypeDef *) WDOG_BASE) /**< WDOG base pointer */ |
||||
#define ETM ((ETM_TypeDef *) ETM_BASE) /**< ETM 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 EZR32WG330F256R60_Peripheral_Declaration */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_BitFields EZR32WG330F256R60 Bit Fields |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
#include "ezr32wg_prs_signals.h" |
||||
#include "ezr32wg_dmareq.h" |
||||
#include "ezr32wg_dmactrl.h" |
||||
#include "ezr32wg_usartrf.h" |
||||
#include "ezr32wg_uart.h" |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_UNLOCK EZR32WG330F256R60 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 */ |
||||
#define BURTC_UNLOCK_CODE 0xAEE8 /**< BURTC unlock code */ |
||||
|
||||
/** @} End of group EZR32WG330F256R60_UNLOCK */ |
||||
|
||||
/** @} End of group EZR32WG330F256R60_BitFields */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG330F256R60_Alternate_Function EZR32WG330F256R60 Alternate Function |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
#include "ezr32wg_af_ports.h" |
||||
#include "ezr32wg_af_pins.h" |
||||
|
||||
/** @} End of group EZR32WG330F256R60_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 EZR32WG330F256R60 */ |
||||
|
||||
/** @} End of group Parts */ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
#endif /* __SILICON_LABS_EZR32WG330F256R60_H__ */ |
@ -0,0 +1,329 @@
|
||||
/**************************************************************************//**
|
||||
* @file ezr32wg_acmp.h |
||||
* @brief EZR32WG_ACMP register and bit field definitions |
||||
* @version 4.0.0 |
||||
****************************************************************************** |
||||
* @section License |
||||
* <b>(C) Copyright 2015 Silicon Laboratories, Inc. http://www.silabs.com</b>
|
||||
****************************************************************************** |
||||
* |
||||
* 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.@n |
||||
* 2. Altered source versions must be plainly marked as such, and must not be |
||||
* misrepresented as being the original software.@n |
||||
* 3. This notice may not be removed or altered from any source distribution. |
||||
* |
||||
* DISCLAIMER OF WARRANTY/LIMITATION OF REMEDIES: Silicon Laboratories, Inc. |
||||
* has no obligation to support this Software. Silicon Laboratories, Inc. is |
||||
* providing the Software "AS IS", with no express or implied warranties of any |
||||
* kind, including, but not limited to, any implied warranties of |
||||
* merchantability or fitness for any particular purpose or warranties against |
||||
* infringement of any proprietary rights of a third party. |
||||
* |
||||
* Silicon Laboratories, Inc. will not be liable for any consequential, |
||||
* incidental, or special damages, or any other relief, or for any claim by |
||||
* any third party, arising from your use of this Software. |
||||
* |
||||
*****************************************************************************/ |
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG_ACMP |
||||
* @{ |
||||
* @brief EZR32WG_ACMP Register Declaration |
||||
*****************************************************************************/ |
||||
typedef struct |
||||
{ |
||||
__IO uint32_t CTRL; /**< Control Register */ |
||||
__IO uint32_t INPUTSEL; /**< Input Selection Register */ |
||||
__I uint32_t STATUS; /**< Status Register */ |
||||
__IO uint32_t IEN; /**< Interrupt Enable Register */ |
||||
__I uint32_t IF; /**< Interrupt Flag Register */ |
||||
__IO uint32_t IFS; /**< Interrupt Flag Set Register */ |
||||
__IO uint32_t IFC; /**< Interrupt Flag Clear Register */ |
||||
__IO uint32_t ROUTE; /**< I/O Routing Register */ |
||||
} ACMP_TypeDef; /** @} */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG_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_DAC0CH0 0x0000000CUL /**< Mode DAC0CH0 for ACMP_INPUTSEL */ |
||||
#define _ACMP_INPUTSEL_NEGSEL_DAC0CH1 0x0000000DUL /**< Mode DAC0CH1 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_NEGSEL_DAC0CH0 (_ACMP_INPUTSEL_NEGSEL_DAC0CH0 << 4) /**< Shifted mode DAC0CH0 for ACMP_INPUTSEL */ |
||||
#define ACMP_INPUTSEL_NEGSEL_DAC0CH1 (_ACMP_INPUTSEL_NEGSEL_DAC0CH1 << 4) /**< Shifted mode DAC0CH1 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 EZR32WG_ACMP */ |
@ -0,0 +1,668 @@
|
||||
/**************************************************************************//**
|
||||
* @file ezr32wg_adc.h |
||||
* @brief EZR32WG_ADC register and bit field definitions |
||||
* @version 4.0.0 |
||||
****************************************************************************** |
||||
* @section License |
||||
* <b>(C) Copyright 2015 Silicon Laboratories, Inc. http://www.silabs.com</b>
|
||||
****************************************************************************** |
||||
* |
||||
* 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.@n |
||||
* 2. Altered source versions must be plainly marked as such, and must not be |
||||
* misrepresented as being the original software.@n |
||||
* 3. This notice may not be removed or altered from any source distribution. |
||||
* |
||||
* DISCLAIMER OF WARRANTY/LIMITATION OF REMEDIES: Silicon Laboratories, Inc. |
||||
* has no obligation to support this Software. Silicon Laboratories, Inc. is |
||||
* providing the Software "AS IS", with no express or implied warranties of any |
||||
* kind, including, but not limited to, any implied warranties of |
||||
* merchantability or fitness for any particular purpose or warranties against |
||||
* infringement of any proprietary rights of a third party. |
||||
* |
||||
* Silicon Laboratories, Inc. will not be liable for any consequential, |
||||
* incidental, or special damages, or any other relief, or for any claim by |
||||
* any third party, arising from your use of this Software. |
||||
* |
||||
*****************************************************************************/ |
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG_ADC |
||||
* @{ |
||||
* @brief EZR32WG_ADC Register Declaration |
||||
*****************************************************************************/ |
||||
typedef struct |
||||
{ |
||||
__IO uint32_t CTRL; /**< Control Register */ |
||||
__IO uint32_t CMD; /**< Command Register */ |
||||
__I uint32_t STATUS; /**< Status Register */ |
||||
__IO uint32_t SINGLECTRL; /**< Single Sample Control Register */ |
||||
__IO uint32_t SCANCTRL; /**< Scan Control Register */ |
||||
__IO uint32_t IEN; /**< Interrupt Enable Register */ |
||||
__I uint32_t IF; /**< Interrupt Flag Register */ |
||||
__IO uint32_t IFS; /**< Interrupt Flag Set Register */ |
||||
__IO uint32_t IFC; /**< Interrupt Flag Clear Register */ |
||||
__I uint32_t SINGLEDATA; /**< Single Conversion Result Data */ |
||||
__I uint32_t SCANDATA; /**< Scan Conversion Result Data */ |
||||
__I uint32_t SINGLEDATAP; /**< Single Conversion Result Data Peek Register */ |
||||
__I uint32_t SCANDATAP; /**< Scan Sequence Result Data Peek Register */ |
||||
__IO uint32_t CAL; /**< Calibration Register */ |
||||
|
||||
uint32_t RESERVED0[1]; /**< Reserved for future use **/ |
||||
__IO uint32_t BIASPROG; /**< Bias Programming Register */ |
||||
} ADC_TypeDef; /** @} */ |
||||
|
||||
/**************************************************************************//**
|
||||
* @defgroup EZR32WG_ADC_BitFields |
||||
* @{ |
||||
*****************************************************************************/ |
||||
|
||||
/* Bit fields for ADC CTRL */ |
||||
#define _ADC_CTRL_RESETVALUE 0x001F0000UL /**< Default value for ADC_CTRL */ |
||||
#define _ADC_CTRL_MASK 0x0F7F7F3BUL /**< 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 */ |
||||
|
||||
/* 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 0xF1F70F37UL /**< 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 0xF0000000UL /**< 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 */ |