From fbbe7faf446537c2d80a3d4f85ecaa49c9d13dee Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 7 May 2009 20:52:29 +0000 Subject: Add definitions for system control registers git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1759 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lm3s/chip.h | 1 + nuttx/arch/arm/src/lm3s/lm3s_memorymap.h | 78 +++--- nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h | 449 ++++++++++++++++++++++++++++++ 3 files changed, 489 insertions(+), 39 deletions(-) create mode 100644 nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/lm3s/chip.h b/nuttx/arch/arm/src/lm3s/chip.h index aa6905fc1..a3a2f6831 100644 --- a/nuttx/arch/arm/src/lm3s/chip.h +++ b/nuttx/arch/arm/src/lm3s/chip.h @@ -44,6 +44,7 @@ #include #include "lm3s_memorymap.h" /* Memory map */ +#include "lm3s_syscontrol.h" /* System control module */ /************************************************************************************ * Definitions diff --git a/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h b/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h index df49a5f3e..df8fc0460 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h +++ b/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h @@ -56,8 +56,8 @@ /* -0x21ffffff: Reserved */ # define LM3S_ASRAM_BASE 0x22000000 /* -0x221fffff: Bit-band alias of 20000000- */ /* -0x3fffffff: Reserved */ -# define LM3S_FPERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */ -# define LM3S_PERIPH_BASE 0x40020000 /* -0x41ffffff: Peripherals */ +# define LM3S_PERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */ + /* -0x41ffffff: Peripherals */ # define LM3S_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alise of 40000000- */ /* -0xdfffffff: Reserved */ # define LM3S_ITM_BASE 0xe0000000 /* -0xe0000fff: Instrumentation Trace Macrocell */ @@ -77,45 +77,45 @@ #ifdef CONFIG_ARCH_CHIP_LM3S6918 /* FiRM Peripheral Base Addresses */ -# define LM3S_WDOG_BASE (LM3S_FPERIPH_BASE + 0x00000) /* -0x00fff: Watchdog Timer */ - /* -0x03fff: Reserved */ -# define LM3S_GPIOA_BASE (LM3S_FPERIPH_BASE + 0x04000) /* -0x04fff: GPIO Port A */ -# define LM3S_GPIOB_BASE (LM3S_FPERIPH_BASE + 0x05000) /* -0x05fff: GPIO Port B */ -# define LM3S_GPIOC_BASE (LM3S_FPERIPH_BASE + 0x06000) /* -0x06fff: GPIO Port C */ -# define LM3S_GPIOD_BASE (LM3S_FPERIPH_BASE + 0x07000) /* -0x07fff: GPIO Port D */ -# define LM3S_SSI0_BASE (LM3S_FPERIPH_BASE + 0x08000) /* -0x08fff: SSI0 */ -# define LM3S_SSI1_BASE (LM3S_FPERIPH_BASE + 0x09000) /* -0x09fff: SSI1 */ - /* -0x0bfff: Reserved */ -# define LM3S_UART0_BASE (LM3S_FPERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ -# define LM3S_UART1_BASE (LM3S_FPERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ - /* -0x1ffff: Reserved */ +# define LM3S_WDOG_BASE (LM3S_PERIPH_BASE + 0x00000) /* -0x00fff: Watchdog Timer */ + /* -0x03fff: Reserved */ +# define LM3S_GPIOA_BASE (LM3S_PERIPH_BASE + 0x04000) /* -0x04fff: GPIO Port A */ +# define LM3S_GPIOB_BASE (LM3S_PERIPH_BASE + 0x05000) /* -0x05fff: GPIO Port B */ +# define LM3S_GPIOC_BASE (LM3S_PERIPH_BASE + 0x06000) /* -0x06fff: GPIO Port C */ +# define LM3S_GPIOD_BASE (LM3S_PERIPH_BASE + 0x07000) /* -0x07fff: GPIO Port D */ +# define LM3S_SSI0_BASE (LM3S_PERIPH_BASE + 0x08000) /* -0x08fff: SSI0 */ +# define LM3S_SSI1_BASE (LM3S_PERIPH_BASE + 0x09000) /* -0x09fff: SSI1 */ + /* -0x0bfff: Reserved */ +# define LM3S_UART0_BASE (LM3S_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ +# define LM3S_UART1_BASE (LM3S_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ + /* -0x1ffff: Reserved */ /* Peripheral Base Addresses */ -# define LM3S_I2CM0_BASE (LM3S_PERIPH_BASE + 0x00000) /* -0x007ff: I2C Master 0 */ -# define LM3S_I2CS0_BASE (LM3S_PERIPH_BASE + 0x00800) /* -0x00fff: I2C Slave 0 */ -# define LM3S_I2CM1_BASE (LM3S_PERIPH_BASE + 0x01000) /* -0x017ff: I2C Master 1 */ -# define LM3S_I2CS1_BASE (LM3S_PERIPH_BASE + 0x01800) /* -0x01fff: I2C Slave 1 */ - /* -0x03fff: Reserved */ -# define LM3S_GPIOE_BASE (LM3S_PERIPH_BASE + 0x04000) /* -0x04fff: GPIO Port E */ -# define LM3S_GPIOF_BASE (LM3S_PERIPH_BASE + 0x05000) /* -0x05fff: GPIO Port F */ -# define LM3S_GPIOG_BASE (LM3S_PERIPH_BASE + 0x06000) /* -0x06fff: GPIO Port G */ -# define LM3S_GPIOH_BASE (LM3S_PERIPH_BASE + 0x07000) /* -0x07fff: GPIO Port H */ - /* -0x0ffff: Reserved */ -# define LM3S_TIMER0_BASE (LM3S_PERIPH_BASE + 0x10000) /* -0x10fff: Timer 0 */ -# define LM3S_TIMER1_BASE (LM3S_PERIPH_BASE + 0x11000) /* -0x11fff: Timer 1 */ -# define LM3S_TIMER2_BASE (LM3S_PERIPH_BASE + 0x12000) /* -0x12fff: Timer 2 */ -# define LM3S_TIMER3_BASE (LM3S_PERIPH_BASE + 0x13000) /* -0x13fff: Timer 3 */ - /* -0x17fff: Reserved */ -# define LM3S_ADC_BASE (LM3S_PERIPH_BASE + 0x18000) /* -0x18fff: ADC */ - /* -0x1bfff: Reserved */ -# define LM3S_COMPARE_BASE (LM3S_PERIPH_BASE + 0x1c000) /* -0x1cfff: Analog Comparators */ - /* -0x27fff: Reserved */ -# define LM3S_ETHCON_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: Ethernet Controller */ - /* -0xdcfff: Reserved */ -# define LM3S_HIBERNATE_BASE (LM3S_PERIPH_BASE + 0xdc000) /* -0xdcfff: Ethernet Controller */ -# define LM3S_FLASHCON_BASE (LM3S_PERIPH_BASE + 0xdd000) /* -0xddfff: FLASH Control */ -# define LM3S_SYSCON_BASE (LM3S_PERIPH_BASE + 0xde000) /* -0xdefff: System Control */ - /* -0x1fdffff: Reserved */ +# define LM3S_I2CM0_BASE (LM3S_PERIPH_BASE + 0x20000) /* -0x207ff: I2C Master 0 */ +# define LM3S_I2CS0_BASE (LM3S_PERIPH_BASE + 0x20800) /* -0x20fff: I2C Slave 0 */ +# define LM3S_I2CM1_BASE (LM3S_PERIPH_BASE + 0x21000) /* -0x217ff: I2C Master 1 */ +# define LM3S_I2CS1_BASE (LM3S_PERIPH_BASE + 0x21800) /* -0x21fff: I2C Slave 1 */ + /* -0x23fff: Reserved */ +# define LM3S_GPIOE_BASE (LM3S_PERIPH_BASE + 0x24000) /* -0x24fff: GPIO Port E */ +# define LM3S_GPIOF_BASE (LM3S_PERIPH_BASE + 0x25000) /* -0x25fff: GPIO Port F */ +# define LM3S_GPIOG_BASE (LM3S_PERIPH_BASE + 0x26000) /* -0x26fff: GPIO Port G */ +# define LM3S_GPIOH_BASE (LM3S_PERIPH_BASE + 0x27000) /* -0x27fff: GPIO Port H */ + /* -0x2ffff: Reserved */ +# define LM3S_TIMER0_BASE (LM3S_PERIPH_BASE + 0x30000) /* -0x30fff: Timer 0 */ +# define LM3S_TIMER1_BASE (LM3S_PERIPH_BASE + 0x31000) /* -0x31fff: Timer 1 */ +# define LM3S_TIMER2_BASE (LM3S_PERIPH_BASE + 0x32000) /* -0x32fff: Timer 2 */ +# define LM3S_TIMER3_BASE (LM3S_PERIPH_BASE + 0x33000) /* -0x33fff: Timer 3 */ + /* -0x37fff: Reserved */ +# define LM3S_ADC_BASE (LM3S_PERIPH_BASE + 0x38000) /* -0x38fff: ADC */ + /* -0x3bfff: Reserved */ +# define LM3S_COMPARE_BASE (LM3S_PERIPH_BASE + 0x3c000) /* -0x3cfff: Analog Comparators */ + /* -0x47fff: Reserved */ +# define LM3S_ETHCON_BASE (LM3S_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ + /* -0xfcfff: Reserved */ +# define LM3S_HIBERNATE_BASE (LM3S_PERIPH_BASE + 0xfc000) /* -0xfcfff: Ethernet Controller */ +# define LM3S_FLASHCON_BASE (LM3S_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ +# define LM3S_SYSCON_BASE (LM3S_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ + /* -0x1ffffff: Reserved */ #else # error "Peripheral base addresses not specified for this LM3S chip" #endif diff --git a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h b/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h new file mode 100644 index 000000000..ca3550d43 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h @@ -0,0 +1,449 @@ +/************************************************************************************ + * arch/arm/src/lm3s/lm3s_syscontrol.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_LM3S_LM3S_SYSCONTROL_H +#define __ARCH_ARM_SRC_LM3S_LM3S_SYSCONTROL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* System Control Register Offsets **************************************************/ + +#ifdef CONFIG_ARCH_CHIP_LM3S6918 + +#define LM3S_SYSCON_DID0_OFFSET 0x000 /* Device Identification 0 */ +#define LM3S_SYSCON_DID1_OFFSET 0x004 /* Device Identification 1 */ +#define LM3S_SYSCON_DC0_OFFSET 0x008 /* Device Capabilities 0 */ +#define LM3S_SYSCON_DC1_OFFSET 0x010 /* Device Capabilities 1 */ +#define LM3S_SYSCON_DC2_OFFSET 0x014 /* Device Capabilities 2 */ +#define LM3S_SYSCON_DC3_OFFSET 0x018 /* Device Capabilities 3 */ +#define LM3S_SYSCON_DC4_OFFSET 0x01c /* Device Capabilities 4 */ +#define LM3S_SYSCON_PBORCTL_OFFSET 0x030 /* Brown-Out Reset Control */ +#define LM3S_SYSCON_LDOPCTL_OFFSET 0x034 /* LDO Power Control */ +#define LM3S_SYSCON_SRCR0_OFFSET 0x040 /* Software Reset Control 0 */ +#define LM3S_SYSCON_SRCR1_OFFSET 0x044 /* Software Reset Control 1 */ +#define LM3S_SYSCON_SRCR2_OFFSET 0x048 /* Software Reset Control 2*/ +#define LM3S_SYSCON_RIS_OFFSET 0x050 /* Raw Interrupt Status */ +#define LM3S_SYSCON_IMC_OFFSET 0x054 /* Interrupt Mask Control */ +#define LM3S_SYSCON_MISC_OFFSET 0x058 /* Masked Interrupt Status and Clear */ +#define LM3S_SYSCON_RESC_OFFSET 0x05c /* Reset Cause */ +#define LM3S_SYSCON_RCC_OFFSET 0x060 /* Run-Mode Clock Configuration */ +#define LM3S_SYSCON_PLLCFG_OFFSET 0x064 /* XTAL to PLL Translation */ +#define LM3S_SYSCON_RCC2_OFFSET 0x070 /* Run-Mode Clock Configuration 2 */ +#define LM3S_SYSCON_RCGC0_OFFSET 0x100 /* Run Mode Clock Gating Control Register 0 */ +#define LM3S_SYSCON_RCGC1_OFFSET 0x104 /* Run Mode Clock Gating Control Register 1 */ +#define LM3S_SYSCON_RCGC2_OFFSET 0x108 /* Run Mode Clock Gating Control Register 2 */ +#define LM3S_SYSCON_SCGC0_OFFSET 0x110 /* Sleep Mode Clock Gating Control Register 0 */ +#define LM3S_SYSCON_SCGC1_OFFSET 0x114 /* Sleep Mode Clock Gating Control Register 1 */ +#define LM3S_SYSCON_SCGC2_OFFSET 0x118 /* Sleep Mode Clock Gating Control Register 2 */ +#define LM3S_SYSCON_DCGC0_OFFSET 0x120 /* Deep Sleep Mode Clock Gating Control Register 0 */ +#define LM3S_SYSCON_DCGC1_OFFSET 0x124 /* Deep Sleep Mode Clock Gating Control Register 1 */ +#define LM3S_SYSCON_DCGC2_OFFSET 0x128 /* Deep Sleep Mode Clock Gating Control Register 2 */ +#define LM3S_SYSCON_DSLPCLKCFG_OFFSET 0x144 /* Deep Sleep Clock Configuration*/ +#else +# error "Peripheral base addresses not specified for this LM3S chip" +#endif + +/* System Control Register Addresses ************************************************/ + +#define LM3S_SYSCON_DID0 (LM3S_SYSCON_BASE + LM3S_SYSCON_DID0_OFFSET) +#define LM3S_SYSCON_DID1 (LM3S_SYSCON_BASE + LM3S_SYSCON_DID1_OFFSET) +#define LM3S_SYSCON_DC0 (LM3S_SYSCON_BASE + LM3S_SYSCON_DC0_OFFSET) +#define LM3S_SYSCON_DC1 (LM3S_SYSCON_BASE + LM3S_SYSCON_DC1_OFFSET) +#define LM3S_SYSCON_DC2 (LM3S_SYSCON_BASE + LM3S_SYSCON_DC2_OFFSET) +#define LM3S_SYSCON_DC3 (LM3S_SYSCON_BASE + LM3S_SYSCON_DC3_OFFSET) +#define LM3S_SYSCON_DC4 (LM3S_SYSCON_BASE + LM3S_SYSCON_DC4_OFFSET) +#define LM3S_SYSCON_PBORCTL (LM3S_SYSCON_BASE + LM3S_SYSCON_PBORCTL_OFFSET) +#define LM3S_SYSCON_LDOPCTL (LM3S_SYSCON_BASE + LM3S_SYSCON_LDOPCTL_OFFSET) +#define LM3S_SYSCON_SRCR0 (LM3S_SYSCON_BASE + LM3S_SYSCON_SRCR0_OFFSET) +#define LM3S_SYSCON_SRCR1 (LM3S_SYSCON_BASE + LM3S_SYSCON_SRCR1_OFFSET) +#define LM3S_SYSCON_SRCR2 (LM3S_SYSCON_BASE + LM3S_SYSCON_SRCR2_OFFSET) +#define LM3S_SYSCON_RIS (LM3S_SYSCON_BASE + LM3S_SYSCON_RIS_OFFSET) +#define LM3S_SYSCON_IMC (LM3S_SYSCON_BASE + LM3S_SYSCON_IMC_OFFSET) +#define LM3S_SYSCON_MISC (LM3S_SYSCON_BASE + LM3S_SYSCON_MISC_OFFSET) +#define LM3S_SYSCON_RESC (LM3S_SYSCON_BASE + LM3S_SYSCON_RESC_OFFSET) +#define LM3S_SYSCON_RCC (LM3S_SYSCON_BASE + LM3S_SYSCON_RCC_OFFSET) +#define LM3S_SYSCON_PLLCFG (LM3S_SYSCON_BASE + LM3S_SYSCON_PLLCFG_OFFSET) +#define LM3S_SYSCON_RCC2 (LM3S_SYSCON_BASE + LM3S_SYSCON_RCC2_OFFSET) +#define LM3S_SYSCON_RCGC0 (LM3S_SYSCON_BASE + LM3S_SYSCON_RCGC0_OFFSET) +#define LM3S_SYSCON_RCGC1 (LM3S_SYSCON_BASE + LM3S_SYSCON_RCGC1_OFFSET) +#define LM3S_SYSCON_RCGC2 (LM3S_SYSCON_BASE + LM3S_SYSCON_RCGC2_OFFSET) +#define LM3S_SYSCON_SCGC0 (LM3S_SYSCON_BASE + LM3S_SYSCON_SCGC0_OFFSET) +#define LM3S_SYSCON_SCGC1 (LM3S_SYSCON_BASE + LM3S_SYSCON_SCGC1_OFFSET) +#define LM3S_SYSCON_SCGC2 (LM3S_SYSCON_BASE + LM3S_SYSCON_SCGC2_OFFSET) +#define LM3S_SYSCON_DCGC0 (LM3S_SYSCON_BASE + LM3S_SYSCON_DCGC0_OFFSET) +#define LM3S_SYSCON_DCGC1 (LM3S_SYSCON_BASE + LM3S_SYSCON_DCGC1_OFFSET) +#define LM3S_SYSCON_DCGC2 (LM3S_SYSCON_BASE + LM3S_SYSCON_DCGC2_OFFSET) +#define LM3S_SYSCON_DSLPCLKCFG (LM3S_SYSCON_BASE + LM3S_SYSCON_DSLPCLKCFG_OFFSET) + +/* System Control Register Bit Definitions ******************************************/ + +/* Device Identification 0 (DID0), offset 0x000 */ + +#define SYSCON_DID0_MINOR_SHIFT 0 /* Bits 7-0: Minor Revision of the device */ +#define SYSCON_DID0_MINRO_MASK (0xff << SYSCON_DID0_MINOR_SHIFT) +#define SYSCON_DID0_MAJOR_SHIFT 8 /* Bits 15-8: Major Revision of the device */ +#define SYSCON_DID0_MAJOR_MASK (0xff << SYSCON_DID0_MAJOR_SHIFT) +#define SYSCON_DID0_CLASS_SHIFT 16 /* Bits 23-16: Device Class */ +#define SYSCON_DID0_CLASS_MASK (0xff << SYSCON_DID0_CLASS_SHIFT) +#define SYSCON_DID0_VER_SHIFT 28 /* Bits 30-28: DID0 Version */ +#define SYSCON_DID0_VER_MASK (7 << SYSCON_DID0_VER_SHIFT) + +/* Device Identification 1 (DID1), offset 0x004 */ + +#define SYSCON_DID1_QUAL_SHIFT 0 /* Bits 1-0: Qualification Status */ +#define SYSCON_DID1_QUAL_MASK (0x03 << SYSCON_DID1_QUAL_SHIFT) +#define SYSCON_DID1_ROHS (1 << 2) /* Bit 2: RoHS-Compliance */ +#define SYSCON_DID1_PKG_SHIFT 3 /* Bits 4-3: Package Type */ +#define SYSCON_DID1_PKG_MASK (0x03 << SYSCON_DID1_PKG_SHIFT) +#define SYSCON_DID1_TEMP_SHIFT 5 /* Bits 7-5: Temperature Range */ +#define SYSCON_DID1_TEMP_MASK (0x07 << SYSCON_DID1_TEMP_SHIFT) +#define SYSCON_DID1_PINCOUNT_SHIFT 13 /* Bits 15-13: Package Pin Count */ +#define SYSCON_DID1_PINCOUNT_MASK (0x07 << SYSCON_DID1_PINCOUNT_SHIFT) +#define SYSCON_DID1_PARTNO_SHIFT 16 /* Bits 23-16: Part Number */ +#define SYSCON_DID1_PARTNO_MASK (0xff << SYSCON_DID1_PARTNO_SHIFT) +#define SYSCON_DID1_FAM_SHIFT 24 /* Bits 27-24: Family */ +#define SYSCON_DID1_FAM_MASK (0x0f << SYSCON_DID1_FAM_SHIFT) +#define SYSCON_DID1_VER_SHIFT 28 /* Bits 31-28: DID1 Version */ +#define SYSCON_DID1_VER_MASK (0x0f << SYSCON_DID1_VER_SHIFT) + +/* Device Capabilities 0 (DC0), offset 0x008 */ + +#define SYSCON_DC0_FLASHSZ_SHIFT 0 /* Bits 15-0: FLASH Size */ +#define SYSCON_DC0_FLASHSZ_MASK (0xffff << SYSCON_DC0_FLASHSZ_SHIFT) +#define SYSCON_DC0_SRAMSZ_SHIFT 16 /* Bits 31-16: SRAM Size */ +#define SYSCON_DC0_SRAMSZ_MASK (0xffff << SYSCON_DC0_SRAMSZ_SHIFT) + +/* Device Capabilities 1 (DC1), offset 0x010 */ + +#define SYSCON_DC1_JTAG (1 << 0) /* Bit 0: JTAG Present */ +#define SYSCON_DC1_SWD (1 << 1) /* Bit 1: SWD Present */ +#define SYSCON_DC1_SWO (1 << 2) /* Bit 2: SWO Trace Port Present */ +#define SYSCON_DC1_WDT (1 << 3) /* Bit 3: Watchdog Timer Present */ +#define SYSCON_DC1_PLL (1 << 4) /* Bit 4: PLL Present */ +#define SYSCON_DC1_TEMPSNS (1 << 5) /* Bit 5: Temp Sensor Present */ +#define SYSCON_DC1_HIB (1 << 6) /* Bit 6: Hibernation Module Present */ +#define SYSCON_DC1_MPU (1 << 7) /* Bit 7: MPU Present */ +#define SYSCON_DC1_MAXADCSPD_SHIFT 8 /* Bits 9-8: Max ADC Speed */ +#define SYSCON_DC1_MAXADCSPD_MASK (0x03 << SYSCON_DC1_MAXADCSPD_SHIFT) +#define SYSCON_DC1_ADC (1 << 16) /* Bit 16: ADC Module Present */ +#define SYSCON_DC1_MINSYSDIV_SHIFT 12 /* Bits 15-12: System Clock Divider Minimum */ +#define SYSCON_DC1_MINSYSDIV_MASK (0x0f << SYSCON_DC1_MINSYSDIV_SHIFT) + +/* Device Capabilities 2 (DC2), offset 0x014 */ + +#define SYSCON_DC2_UART0 (1 << 0) /* Bit 0: UART0 Present */ +#define SYSCON_DC2_UART1 (1 << 1) /* Bit 1: UART1 Present */ +#define SYSCON_DC2_SSI0 (1 << 4) /* Bit 4: SSI0 Present */ +#define SYSCON_DC2_SSI1 (1 << 5) /* Bit 5: SSI1 Present */ +#define SYSCON_DC2_I2C0 (1 << 12) /* Bit 12: I2C Module 0 Present */ +#define SYSCON_DC2_I2C1 (1 << 14) /* Bit 14: I2C Module 1 Present */ +#define SYSCON_DC2_TIMER0 (1 << 16) /* Bit 16: Timer 0 Present */ +#define SYSCON_DC2_TIMER1 (1 << 17) /* Bit 17: Timer 1 Present */ +#define SYSCON_DC2_TIMER2 (1 << 18) /* Bit 18: Timer 2 Present */ +#define SYSCON_DC2_TIMER3 (1 << 19) /* Bit 19: Timer 3 Present */ +#define SYSCON_DC2_COMP0 (1 << 24) /* Bit 24: Analog Comparator 0 Present */ +#define SYSCON_DC2_COMP1 (1 << 25) /* Bit 25: Analog Comparator 1 Present */ + +/* Device Capabilities 3 (DC3), offset 0x018 */ + +#define SYSCON_DC3_C0MINUS (1 << 6) /* Bit 6: C0- Pin Present */ +#define SYSCON_DC3_C0PLUS (1 << 7) /* Bit 7: C0+ Pin Present */ +#define SYSCON_DC3_C0O (1 << 8) /* Bit 8: C0o Pin Present */ +#define SYSCON_DC3_C1MINUS (1 << 9) /* Bit 9: C1- Pin Present */ +#define SYSCON_DC3_C1PLUS (1 << 10) /* Bit 10: C1+ Pin Present */ +#define SYSCON_DC3_ADC0 (1 << 16) /* Bit 16: ADC0 Pin Present */ +#define SYSCON_DC3_ADC1 (1 << 17) /* Bit 17: ADC1 Pin Present */ +#define SYSCON_DC3_ADC2 (1 << 18) /* Bit 18: ADC2 Pin Present */ +#define SYSCON_DC3_ADC3 (1 << 19) /* Bit 19: ADC3 Pin Present */ +#define SYSCON_DC3_ADC4 (1 << 20) /* Bit 20: ADC4 Pin Present */ +#define SYSCON_DC3_ADC5 (1 << 21) /* Bit 21: ADC5 Pin Present */ +#define SYSCON_DC3_ADC6 (1 << 22) /* Bit 22: ADC6 Pin Present */ +#define SYSCON_DC3_ADC7 (1 << 23) /* Bit 23: ADC7 Pin Present */ +#define SYSCON_DC3_CCP0 (1 << 24) /* Bit 24: CCP0 Pin Present */ +#define SYSCON_DC3_CCP1 (1 << 25) /* Bit 25: CCP1 Pin Present */ +#define SYSCON_DC3_CCP2 (1 << 26) /* Bit 26: CCP2 Pin Present */ +#define SYSCON_DC3_CCP3 (1 << 27) /* Bit 27: CCP3 Pin Present */ +#define SYSCON_DC3_CCP4 (1 << 28) /* Bit 28: CCP4 Pin Present */ +#define SYSCON_DC3_CCP5 (1 << 29) /* Bit 29: CCP5 Pin Present */ +#define SYSCON_DC3_32KHZ (1 << 31) /* Bit 31: 32KHz Input Clock Available */ + +/* Device Capabilities 4 (DC4), offset 0x01c */ + +#define SYSCON_DC4_GPIOA (1 << 0) /* Bit 0: GPIO Port A Present */ +#define SYSCON_DC4_GPIOB (1 << 1) /* Bit 1: GPIO Port B Present */ +#define SYSCON_DC4_GPIOC (1 << 2) /* Bit 2: GPIO Port C Present */ +#define SYSCON_DC4_GPIOD (1 << 3) /* Bit 3: GPIO Port D Present */ +#define SYSCON_DC4_GPIOE (1 << 4) /* Bit 4: GPIO Port E Present */ +#define SYSCON_DC4_GPIOF (1 << 5) /* Bit 5: GPIO Port F Present */ +#define SYSCON_DC4_GPIOG (1 << 6) /* Bit 6: GPIO Port G Present */ +#define SYSCON_DC4_GPIOH (1 << 7) /* Bit 7: GPIO Port H Present */ +#define SYSCON_DC4_EMAC0 (1 << 28) /* Bit 28: Ethernet MAC0 Present */ +#define SYSCON_DC4_EPHY0 (1 << 30) /* Bit 30: Ethernet PHY0 Present */ + +/* Brown-Out Reset Control (PBORCTL), offset 0x030 */ + +#define SYSCON_PBORCTL_BORIOR (1 << 1) /* Bit 1: BOR Interrupt or Reset */ + +/* LDO Power Control (LDOPCTL), offset 0x034 */ + +#define SYSCON_LDOPCTL_VADJ_SHIFT 0 /* Bits 5-0: LDO Output Voltage */ +#define SYSCON_LDOPCTL_VADJ_MASK (0x3f << SYSCON_LDOPCTL_VADJ_SHIFT) + +/* Software Reset Control 0 (SRCR0), offset 0x040 */ + +#define SYSCON_SRCR0_WDT (1 << 3) /* Bit 3: WDT Reset Control */ +#define SYSCON_SRCR0_HIB (1 << 6) /* Bit 6: HIB Reset Control */ +#define SYSCON_SRCR0_ADC (1 << 16) /* Bit 16: ADC0 Reset Control */ + +/* Software Reset Control 1 (SRCR1), offset 0x044 */ + +#define SYSCON_SRCR1_UART0 (1 << 0) /* Bit 0: UART0 Reset Control */ +#define SYSCON_SRCR1_UART1 (1 << 1) /* Bit 1: UART1 Reset Control */ +#define SYSCON_SRCR1_SSI0 (1 << 4) /* Bit 4: SSI0 Reset Control1 */ +#define SYSCON_SRCR1_SSI1 (1 << 5) /* Bit 5: SSI1 Reset Control */ +#define SYSCON_SRCR1_I2C0 (1 << 12) /* Bit 12: I2C0 Reset Control */ +#define SYSCON_SRCR1_I2C1 (1 << 14) /* Bit 14: I2C1 Reset Control */ +#define SYSCON_SRCR1_TIMER0 (1 << 16) /* Bit 16: Timer 0 Reset Control */ +#define SYSCON_SRCR1_TIMER1 (1 << 17) /* Bit 17: Timer 1 Reset Control */ +#define SYSCON_SRCR1_TIMER2 (1 << 18) /* Bit 18: Timer 2 Reset Control */ +#define SYSCON_SRCR1_TIMER3 (1 << 19) /* Bit 19: Timer 3 Reset Control */ +#define SYSCON_SRCR1_COMP0 (1 << 24) /* Bit 24: Analog Comp 0 Reset Control */ +#define SYSCON_SRCR1_COMP1 (1 << 25) /* Bit 25: Analog Comp 1 Reset Control */ + +/* Software Reset Control 2 (SRCR2), offset 0x048 */ + +#define SYSCON_SRCR2_GPIOA (1 << 0) /* Bit 0: Port A Reset Control */ +#define SYSCON_SRCR2_GPIOB (1 << 1) /* Bit 1: Port B Reset Control */ +#define SYSCON_SRCR2_GPIOC (1 << 2) /* Bit 2: Port C Reset Control */ +#define SYSCON_SRCR2_GPIOD (1 << 3) /* Bit 3: Port D Reset Control */ +#define SYSCON_SRCR2_GPIOE (1 << 4) /* Bit 4: Port E Reset Control */ +#define SYSCON_SRCR2_GPIOF (1 << 5) /* Bit 5: Port F Reset Control */ +#define SYSCON_SRCR2_GPIOG (1 << 6) /* Bit 6: Port G Reset Control */ +#define SYSCON_SRCR2_GPIOH (1 << 7) /* Bit 7: Port H Reset Control */ +#define SYSCON_SRCR2_EMAC0 (1 << 28) /* Bit 28: MAC0 Reset Control */ +#define SYSCON_SRCR2_EPHY0 (1 << 30) /* Bit 30: PHY0 Reset Control */ + +/* Raw Interrupt Status (RIS), offset 0x050 */ + +#define SYSCON_RIS_BORRIS (1 << 1) /* Bit 1: Brown-Out Reset Raw Interrupt Status */ +#define SYSCON_RIS_PLLLRIS (1 << 6) /* Bit 6: PLL Lock Raw Interrupt Status */ + +/* Interrupt Mask Control (IMC), offset 0x054 */ + +#define SYSCON_IMC_BORIM (1 << 1) /* Bit 1: Brown-Out Reset Interrupt Mask */ +#define SYSCON_IMC_PLLLIM (1 << 6) /* Bit 6: PLL Lock Interrupt Mask */ + +/* Masked Interrupt Status and Clear (MISC), offset 0x058 */ + +#define SYSCON_MISC_BORMIS (1 << 1) /* Bit 1: BOR Masked Interrupt Status */ +#define SYSCON_MISC_PLLLMIS (1 << 6) /* Bit 6: PLL Lock Masked Interrupt Status */ + +/* Reset Cause (RESC), offset 0x05C */ + +#define SYSCON_RESC_EXT (1 << 0) /* Bit 0: External Reset */ +#define SYSCON_RESC_POR (1 << 1) /* Bit 1: Power-On Reset */ +#define SYSCON_RESC_BOR (1 << 2) /* Bit 2: Brown-Out Reset */ +#define SYSCON_RESC_WDT (1 << 3) /* Bit 3: Watchdog Timer Reset */ +#define SYSCON_RESC_SW (1 << 4) /* Bit 4: Software Reset */ + +/* Run-Mode Clock Configuration (RCC), offset 0x060 */ + +#define SYSCON_RCC_MOSCDIS (1 << 0) /* Bit 0: Main Oscillator Disable */ +#define SYSCON_RCC_IOSCDIS (1 << 1) /* Bit 1: Internal Oscillator Disable */ +#define SYSCON_RCC_OSCSRC_SHIFT 4 /* Bits 5-4: Oscillator Source */ +#define SYSCON_RCC_OSCSRC_MASK (0x03 << SYSCON_RCC_OSCSRC_SHIFT) +#define SYSCON_RCC_XTAL_SHIFT 6 /* Bits 9-6: Crystal Value */ +#define SYSCON_RCC_XTAL_MASK (0x0f << SYSCON_RCC_XTAL_SHIFT) +#define SYSCON_RCC_BYPASS (1 << 11) /* Bit 11: PLL Bypass */ +#define SYSCON_RCC_PWRDN (1 << 13) /* Bit 13: PLL Power Down */ +#define SYSCON_RCC_USESYSDIV (1 << 22) /* Bit 22: Enable System Clock Divider */ +#define SYSCON_RCC_SYSDIV_SHIFT 26 /* Bits 26-23: System Clock Divisor */ +#define SYSCON_RCC_SYSDIV_MASK (0x0f << SYSCON_RCC_SYSDIV_SHIFT) +#define SYSCON_RCC_ACG (1 << 27) /* Bit 27: Auto Clock Gating */ + +/* XTAL to PLL Translation (PLLCFG), offset 0x064 */ + +#define SYSCON_PLLCFG_F_SHIFT 5 /* Bits 13-5: PLL F Value */ +#define SYSCON_PLLCFG_F_MASK (0x1ff << SYSCON_PLLCFG_F_SHIFT) +#define SYSCON_PLLCFG_R_SHIFT 0 /* Bits 4-0: PLL R Value */ +#define SYSCON_PLLCFG_R_MASK (0x1f << SYSCON_PLLCFG_R_SHIFT) + +/* Run-Mode Clock Configuration 2 (RCC2), offset 0x070 */ + +#define SYSCON_RCC2_OSCSRC2_SHIFT 4 /* Bits 6-4: Oscillator Source */ +#define SYSCON_RCC2_OSCSRC2_MASK (0x07 << SYSCON_RCC2_OSCSRC2_SHIFT) +#define SYSCON_RCC2_BYPASS2 (1 << 11) /* Bit 11: Bypass PLL */ +#define SYSCON_RCC2_PWRDN2 (1 << 13) /* Bit 13: Power-Down PLL */ +#define SYSCON_RCC2_SYSDIV2_SHIFT 23 /* Bits 28-23: System Clock Divisor */ +#define SYSCON_RCC2_SYSDIV2_MASK (0x3f << SYSCON_RCC2_SYSDIV2_SHIFT) +#define SYSCON_RCC2_USERCC2 (1 << 31) /* Bit 31: Use RCC2 When set */ + +/* Run Mode Clock Gating Control Register 0 (RCGC0), offset 0x100 */ + +#define SYSCON_RCGC0_WDT (1 << 3) /* Bit 3: WDT Clock Gating Control */ +#define SYSCON_RCGC0_HIB (1 << 6) /* Bit 6: HIB Clock Gating Control */ +#define SYSCON_RCGC0_MAXADCSPD_SHIFT 8 /* Bits 9-8: ADC Sample Speed */ +#define SYSCON_RCGC0_MAXADCSPD_MASK (0x03 << SYSCON_RCGC0_MAXADCSPD_SHIFT) +#define SYSCON_RCGC0_ADC (1 << 16) /* Bit 16: ADC0 Clock Gating Control */ + +/* Run Mode Clock Gating Control Register 1 (RCGC1), offset 0x104 */ + +#define SYSCON_RCGC1_UART0 (1 << 0) /* Bit 0: UART0 Clock Gating Control */ +#define SYSCON_RCGC1_UART1 (1 << 1) /* Bit 1: UART1 Clock Gating Control */ +#define SYSCON_RCGC1_SSI0 (1 << 4) /* Bit 4: SSI0 Clock Gating Control */ +#define SYSCON_RCGC1_SSI1 (1 << 5) /* Bit 5: SSI1 Clock Gating Control */ +#define SYSCON_RCGC1_I2C0 (1 << 12) /* Bit 12: I2C0 Clock Gating Control */ +#define SYSCON_RCGC1_I2C1 (1 << 14) /* Bit 14: I2C1 Clock Gating Control */ +#define SYSCON_RCGC1_TIMER0 (1 << 16) /* Bit 16: Timer 0 Clock Gating Control */ +#define SYSCON_RCGC1_TIMER1 (1 << 17) /* Bit 17: Timer 1 Clock Gating Control */ +#define SYSCON_RCGC1_TIMER2 (1 << 18) /* Bit 18: Timer 2 Clock Gating Control */ +#define SYSCON_RCGC1_TIMER3 (1 << 19) /* Bit 19: Timer 3 Clock Gating Control */ +#define SYSCON_RCGC1_COMP0 (1 << 24) /* Bit 24: Analog Comparator 0 Clock Gating */ +#define SYSCON_RCGC1_COMP1 (1 << 25) /* Bit 25: Analog Comparator 1 Clock Gating */ + +/* Run Mode Clock Gating Control Register 2 (RCGC2), offset 0x108 */ + +#define SYSCON_RCGC2_GPIOA (1 << 0) /* Bit 0: Port A Clock Gating Control */ +#define SYSCON_RCGC2_GPIOB (1 << 1) /* Bit 1: Port B Clock Gating Control */ +#define SYSCON_RCGC2_GPIOC (1 << 2) /* Bit 2: Port C Clock Gating Control */ +#define SYSCON_RCGC2_GPIOD (1 << 3) /* Bit 3: Port D Clock Gating Control */ +#define SYSCON_RCGC2_GPIOE (1 << 4) /* Bit 4: Port E Clock Gating Control */ +#define SYSCON_RCGC2_GPIOF (1 << 5) /* Bit 5: Port F Clock Gating Control */ +#define SYSCON_RCGC2_GPIOG (1 << 6) /* Bit 6: Port G Clock Gating Control */ +#define SYSCON_RCGC2_GPIOH (1 << 7) /* Bit 7: Port H Clock Gating Control */ +#define SYSCON_RCGC2_EMAC0 (1 << 28) /* Bit 28: MAC0 Clock Gating Control */ +#define SYSCON_RCGC2_EPHY0 (1 << 30) /* Bit 30: PHY0 Clock Gating Control */ + +/* Sleep Mode Clock Gating Control Register 0 (SCGC0), offset 0x110 */ + +#define SYSCON_SCGC0_WDT (1 << 3) /* Bit 3: WDT Clock Gating Control */ +#define SYSCON_SCGC0_HIB (1 << 6) /* Bit 6: HIB Clock Gating Control */ +#define SYSCON_SCGC0_MAXADCSPD_SHIFT 8 /* Bits 9-8: ADC Sample Speed */ +#define SYSCON_SCGC0_MAXADCSPD_MASK (0x03 << SYSCON_SCGC0_MAXADCSPD_SHIFT) +#define SYSCON_SCGC0_ADC (1 << 16) /* Bit 16: ADC0 Clock Gating Control */ + +/* Sleep Mode Clock Gating Control Register 1 (SCGC1), offset 0x114 */ + +#define SYSCON_SCGC1_UART0 (1 << 0) /* Bit 0: UART0 Clock Gating Control */ +#define SYSCON_SCGC1_UART1 (1 << 1) /* Bit 1: UART1 Clock Gating Control */ +#define SYSCON_SCGC1_SSI0 (1 << 4) /* Bit 4: SSI0 Clock Gating Control */ +#define SYSCON_SCGC1_SSI1 (1 << 5) /* Bit 5: SSI1 Clock Gating Control */ +#define SYSCON_SCGC1_I2C0 (1 << 12) /* Bit 12: I2C0 Clock Gating Control */ +#define SYSCON_SCGC1_I2C1 (1 << 14) /* Bit 14: I2C1 Clock Gating Control */ +#define SYSCON_SCGC1_TIMER0 (1 << 16) /* Bit 16: Timer 0 Clock Gating Control */ +#define SYSCON_SCGC1_TIMER1 (1 << 17) /* Bit 17: Timer 1 Clock Gating Control */ +#define SYSCON_SCGC1_TIMER2 (1 << 18) /* Bit 18: Timer 2 Clock Gating Control */ +#define SYSCON_SCGC1_TIMER3 (1 << 19) /* Bit 19: Timer 3 Clock Gating Control */ +#define SYSCON_SCGC1_COMP0 (1 << 24) /* Bit 24: Analog Comparator 0 Clock Gating */ +#define SYSCON_SCGC1_COMP1 (1 << 25) /* Bit 25: Analog Comparator 1 Clock Gating */ + +/* Sleep Mode Clock Gating Control Register 2 (SCGC2), offset 0x118 */ + +#define SYSCON_SCGC2_GPIOA (1 << 0) /* Bit 0: Port A Clock Gating Control */ +#define SYSCON_SCGC2_GPIOB (1 << 1) /* Bit 1: Port B Clock Gating Control */ +#define SYSCON_SCGC2_GPIOC (1 << 2) /* Bit 2: Port C Clock Gating Control */ +#define SYSCON_SCGC2_GPIOD (1 << 3) /* Bit 3: Port D Clock Gating Control */ +#define SYSCON_SCGC2_GPIOE (1 << 4) /* Bit 4: Port E Clock Gating Control */ +#define SYSCON_SCGC2_GPIOF (1 << 5) /* Bit 5: Port F Clock Gating Control */ +#define SYSCON_SCGC2_GPIOG (1 << 6) /* Bit 6: Port G Clock Gating Control */ +#define SYSCON_SCGC2_GPIOH (1 << 7) /* Bit 7: Port H Clock Gating Control */ +#define SYSCON_SCGC2_EMAC0 (1 << 28) /* Bit 28: MAC0 Clock Gating Control */ +#define SYSCON_SCGC2_EPHY0 (1 << 30) /* Bit 30: PHY0 Clock Gating Control */ + +/* Deep Sleep Mode Clock Gating Control Register 0 (DCGC0), offset 0x120 */ + +#define SYSCON_DCGC0_WDT (1 << 3) /* Bit 3: WDT Clock Gating Control */ +#define SYSCON_DCGC0_HIB (1 << 6) /* Bit 6: HIB Clock Gating Control */ +#define SYSCON_DCGC0_MAXADCSPD_SHIFT 8 /* Bits 9-8: ADC Sample Speed */ +#define SYSCON_DCGC0_MAXADCSPD_MASK (0x03 << SYSCON_DCGC0_MAXADCSPD_SHIFT) +#define SYSCON_DCGC0_ADC (1 << 16) /* Bit 16: ADC0 Clock Gating Control */ + +/* Deep Sleep Mode Clock Gating Control Register 1 (DCGC1), offset 0x124 */ + +#define SYSCON_DCGC1_UART0 (1 << 0) /* Bit 0: UART0 Clock Gating Control */ +#define SYSCON_DCGC1_UART1 (1 << 1) /* Bit 1: UART1 Clock Gating Control */ +#define SYSCON_DCGC1_SSI0 (1 << 4) /* Bit 4: SSI0 Clock Gating Control */ +#define SYSCON_DCGC1_SSI1 (1 << 5) /* Bit 5: SSI1 Clock Gating Control */ +#define SYSCON_DCGC1_I2C0 (1 << 12) /* Bit 12: I2C0 Clock Gating Control */ +#define SYSCON_DCGC1_I2C1 (1 << 14) /* Bit 14: I2C1 Clock Gating Control */ +#define SYSCON_DCGC1_TIMER0 (1 << 16) /* Bit 16: Timer 0 Clock Gating Control */ +#define SYSCON_DCGC1_TIMER1 (1 << 17) /* Bit 17: Timer 1 Clock Gating Control */ +#define SYSCON_DCGC1_TIMER2 (1 << 18) /* Bit 18: Timer 2 Clock Gating Control */ +#define SYSCON_DCGC1_TIMER3 (1 << 19) /* Bit 19: Timer 3 Clock Gating Control */ +#define SYSCON_DCGC1_COMP0 (1 << 24) /* Bit 24: Analog Comparator 0 Clock Gating */ +#define SYSCON_DCGC1_COMP1 (1 << 25) /* Bit 25: Analog Comparator 1 Clock Gating */ + +/* Deep Sleep Mode Clock Gating Control Register 2 (DCGC2), offset 0x128 */ + +#define SYSCON_DCGC2_GPIOA (1 << 0) /* Bit 0: Port A Clock Gating Control */ +#define SYSCON_DCGC2_GPIOB (1 << 1) /* Bit 1: Port B Clock Gating Control */ +#define SYSCON_DCGC2_GPIOC (1 << 2) /* Bit 2: Port C Clock Gating Control */ +#define SYSCON_DCGC2_GPIOD (1 << 3) /* Bit 3: Port D Clock Gating Control */ +#define SYSCON_DCGC2_GPIOE (1 << 4) /* Bit 4: Port E Clock Gating Control */ +#define SYSCON_DCGC2_GPIOF (1 << 5) /* Bit 5: Port F Clock Gating Control */ +#define SYSCON_DCGC2_GPIOG (1 << 6) /* Bit 6: Port G Clock Gating Control */ +#define SYSCON_DCGC2_GPIOH (1 << 7) /* Bit 7: Port H Clock Gating Control */ +#define SYSCON_DCGC2_EMAC0 (1 << 28) /* Bit 28: MAC0 Clock Gating Control */ +#define SYSCON_DCGC2_EPHY0 (1 << 30) /* Bit 30: PHY0 Clock Gating Control */ + +/* Deep Sleep Clock Configuration (DSLPCLKCFG), offset 0x144 */ + +#define SYSCON_DSLPCLKCFG_DSDIVORIDE_SHIFT 23 /* Bits 28-23: Divider Field Override */ +#define SYSCON_DSLPCLKCFG_DSDIVORIDE_MASK (0x3f << SYSCON_DSLPCLKCFG_DSDIVORIDE_SHIFT) +#define SYSCON_DSLPCLKCFG_DSOSCSRC_SHIFT 4 /* Bits 6-4: Clock Source */ +#define SYSCON_DSLPCLKCFG_DSOSCSRC_MASK (0x07 << SYSCON_DSLPCLKCFG_DSOSCSRC_SHIFT) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_LM3S_SYSCONTROL_H */ -- cgit v1.2.3