From 4c8b88b97559ddc6714fc17e9a281a13a65f88c0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 8 Jan 2013 16:25:30 +0000 Subject: Add execv() and execl(); Move lm3s header files for compatibility git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5492 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 12 + nuttx/Documentation/NuttxUserGuide.html | 15 +- nuttx/arch/arm/include/lm3s/chip.h | 123 ++++++ nuttx/arch/arm/src/lm3s/chip.h | 79 +--- nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h | 113 ++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h | 203 ++++++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h | 128 +++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h | 395 ++++++++++++++++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h | 247 ++++++++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h | 360 ++++++++++++++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h | 235 ++++++++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h | 495 +++++++++++++++++++++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h | 125 +++++++ nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h | 347 +++++++++++++++++ nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h | 69 ++++ nuttx/arch/arm/src/lm3s/lm3s_epi.h | 113 ------ nuttx/arch/arm/src/lm3s/lm3s_ethernet.h | 203 ---------- nuttx/arch/arm/src/lm3s/lm3s_flash.h | 128 ------- nuttx/arch/arm/src/lm3s/lm3s_gpio.h | 395 -------------------- nuttx/arch/arm/src/lm3s/lm3s_i2c.h | 247 ------------ nuttx/arch/arm/src/lm3s/lm3s_memorymap.h | 360 ------------------ nuttx/arch/arm/src/lm3s/lm3s_ssi.h | 235 ------------ nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h | 495 ------------------------- nuttx/arch/arm/src/lm3s/lm3s_timer.h | 125 ------- nuttx/arch/arm/src/lm3s/lm3s_uart.h | 347 ----------------- nuttx/binfmt/binfmt_exec.c | 21 +- nuttx/include/nuttx/binfmt/binfmt.h | 3 +- nuttx/include/unistd.h | 7 + nuttx/libc/Kconfig | 48 +++ nuttx/libc/unistd/Make.defs | 4 + nuttx/libc/unistd/lib_execl.c | 146 ++++++++ nuttx/libc/unistd/lib_execv.c | 168 +++++++++ nuttx/tools/cfgdefine.c | 1 + 33 files changed, 3269 insertions(+), 2723 deletions(-) create mode 100644 nuttx/arch/arm/include/lm3s/chip.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h create mode 100644 nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_epi.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_ethernet.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_flash.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_gpio.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_i2c.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_memorymap.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_ssi.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_timer.h delete mode 100644 nuttx/arch/arm/src/lm3s/lm3s_uart.h create mode 100644 nuttx/libc/unistd/lib_execl.c create mode 100644 nuttx/libc/unistd/lib_execv.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index e2d8a586b..ee6b088cf 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3880,4 +3880,16 @@ OS layered architecture. * include/unistd.h, arch/arch/src/*: Implement a simple vfork(). On initial checkin, this API is available only for ARM platforms. + * binfmt/binfmt_exec.c: exec() now sets the priority of the new task + to the same priority as the current task (instead of the arbirtrary + value of 50). + * libc/unisted/lib_execv.c and lib_execl.c: New, somewhat flawed, + implementations of execv() and execl(). + * tools/cfgdefine.c: Strips quotes from CONFIG_EXECFUNCS_SYMTAB + value. + * arch/arm/include/lm3s/chip.h: Move chip definitions into + public include area for compatibility with other architectures. + * arch/arm/src/lm3s/chip: Move register definition header files + into a new chip/ sub-directory. + diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index 5c76737e5..918b69d0f 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -202,6 +202,8 @@ paragraphs.
  • 2.1.6 task_restart
  • 2.1.7 getpid
  • 2.1.8 vfork
  • +
  • 2.1.9 execv
  • +
  • 2.1.10 execl
  • 2.1.1 task_create

    @@ -648,6 +650,9 @@ pid_t vfork(void); Compatible with the Unix interface of the same name.

    +

    2.1.9 execv

    +

    2.1.10 execl

    +
    @@ -6798,6 +6803,12 @@ FAR char *getcwd(FAR char *buf, size_t size); int unlink(FAR const char *pathname); int rmdir(FAR const char *pathname); + +#ifdef CONFIG_LIBC_EXECFUNCS +int execl(FAR const char *path, ...); +int execv(FAR const char *path, FAR char *const argv[]); +#endif + int getopt(int argc, FAR char *const argv[], FAR const char *optstring); @@ -8198,7 +8209,9 @@ notify a task when a message is available on a queue.
  • Driver operations
  • dup
  • dup2
  • +
  • execl
  • eXecute In Place (XIP)
  • +
  • execv
  • exit
  • FAT File System Support
  • fclose
  • @@ -8333,9 +8346,9 @@ notify a task when a message is available on a queue.
  • ROMFS
  • sched_getparam
  • sched_get_priority_max
  • +
  • sched_get_priority_min
  • -
  • sched_get_priority_min
  • sched_get_rr_interval
  • sched_lockcount
  • sched_lock
  • diff --git a/nuttx/arch/arm/include/lm3s/chip.h b/nuttx/arch/arm/include/lm3s/chip.h new file mode 100644 index 000000000..d7e98a461 --- /dev/null +++ b/nuttx/arch/arm/include/lm3s/chip.h @@ -0,0 +1,123 @@ +/************************************************************************************ + * arch/arm/include/lm3s/chip.h + * + * Copyright (C) 2009-2010, 2013 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_INCLUDE_LM3S_CHIP_H +#define __ARCH_ARM_INCLUDE_LM3S_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Get customizations for each supported chip (only the LM3S6918 and 65 right now) */ + +#if defined(CONFIG_ARCH_CHIP_LM3S6918) +# define LM3S_NTIMERS 4 /* Four general purpose timers */ +# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ +# undef LM3S_ETHTS /* No timestamp register */ +# define LM3S_NSSI 2 /* Two SSI modules */ +# define LM3S_NUARTS 2 /* Two UART modules */ +# define LM3S_NI2C 2 /* Two I2C modules */ +# define LM3S_NADC 1 /* One ADC module */ +# define LM2S_NPWM 0 /* No PWM generator modules */ +# define LM3S_NQEI 0 /* No quadrature encoders */ +# define LM3S_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */ +#elif defined(CONFIG_ARCH_CHIP_LM3S6432) +# define LM3S_NTIMERS 3 /* Three general purpose timers */ +# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ +# undef LM3S_ETHTS /* No timestamp register */ +# define LM3S_NSSI 1 /* One SSI module */ +# define LM3S_NUARTS 2 /* Two UART modules */ +# define LM3S_NI2C 1 /* Two I2C modules */ +# define LM3S_NADC 1 /* One ADC module */ +# define LM2S_NPWM 1 /* One PWM generator module */ +# define LM3S_NQEI 0 /* No quadrature encoders */ +# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ +#elif defined(CONFIG_ARCH_CHIP_LM3S6965) +# define LM3S_NTIMERS 4 /* Four general purpose timers */ +# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ +# undef LM3S_ETHTS /* No timestamp register */ +# define LM3S_NSSI 1 /* One SSI module */ +# define LM3S_NUARTS 3 /* Three UART modules */ +# define LM3S_NI2C 2 /* Two I2C modules */ +# define LM3S_NADC 1 /* One ADC module */ +# define LM2S_NPWM 3 /* Three PWM generator modules */ +# define LM3S_NQEI 2 /* Two quadrature encoders */ +# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ +#elif defined(CONFIG_ARCH_CHIP_LM3S9B96) +# define LM3S_NTIMERS 4 /* Four general purpose timers */ +# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ +# undef LM3S_ETHTS /* No timestamp register */ +# define LM3S_NSSI 2 /* Two SSI modules */ +# define LM3S_NUARTS 3 /* Three UART modules */ +# define LM3S_NI2C 2 /* Two I2C modules */ +# define LM3S_NADC 2 /* Two ADC module */ +# define LM3S_CAN 2 /* Two CAN module */ +# define LM3S_NPWM 4 /* Four PWM generator modules */ +# define LM3S_NQEI 2 /* Two quadrature encoders */ +# define LM3S_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */ +#elif defined(CONFIG_ARCH_CHIP_LM3S8962) +# define LM3S_NTIMERS 4 /* Four general purpose timers */ +# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ +# define LM3S_NSSI 1 /* One SSI module */ +# define LM3S_NUARTS 3 /* Two UART modules */ +# define LM3S_NI2C 2 /* One I2C module */ +# define LM3S_NADC 1 /* One ADC module */ +# define LM2S_NPWM 3 /* Three PWM generator modules */ +# define LM3S_NQEI 2 /* Two quadrature encoders */ +# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */ +# define LC3S_CANCONTROLLER 1 /* One CAN controller */ +#else +# error "Capabilities not specified for this LM3S chip" +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#endif /* __ARCH_ARM_INCLUDE_LM3S_CHIP_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip.h b/nuttx/arch/arm/src/lm3s/chip.h index 1e22f6221..1e96b5222 100644 --- a/nuttx/arch/arm/src/lm3s/chip.h +++ b/nuttx/arch/arm/src/lm3s/chip.h @@ -41,83 +41,22 @@ ************************************************************************************/ #include +#include /************************************************************************************ * Pre-processor Definitions ************************************************************************************/ -/* Get customizations for each supported chip (only the LM3S6918 and 65 right now) */ - -#if defined(CONFIG_ARCH_CHIP_LM3S6918) -# define LM3S_NTIMERS 4 /* Four general purpose timers */ -# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ -# undef LM3S_ETHTS /* No timestamp register */ -# define LM3S_NSSI 2 /* Two SSI modules */ -# define LM3S_NUARTS 2 /* Two UART modules */ -# define LM3S_NI2C 2 /* Two I2C modules */ -# define LM3S_NADC 1 /* One ADC module */ -# define LM2S_NPWM 0 /* No PWM generator modules */ -# define LM3S_NQEI 0 /* No quadrature encoders */ -# define LM3S_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */ -#elif defined(CONFIG_ARCH_CHIP_LM3S6432) -# define LM3S_NTIMERS 3 /* Three general purpose timers */ -# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ -# undef LM3S_ETHTS /* No timestamp register */ -# define LM3S_NSSI 1 /* One SSI module */ -# define LM3S_NUARTS 2 /* Two UART modules */ -# define LM3S_NI2C 1 /* Two I2C modules */ -# define LM3S_NADC 1 /* One ADC module */ -# define LM2S_NPWM 1 /* One PWM generator module */ -# define LM3S_NQEI 0 /* No quadrature encoders */ -# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ -#elif defined(CONFIG_ARCH_CHIP_LM3S6965) -# define LM3S_NTIMERS 4 /* Four general purpose timers */ -# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ -# undef LM3S_ETHTS /* No timestamp register */ -# define LM3S_NSSI 1 /* One SSI module */ -# define LM3S_NUARTS 3 /* Three UART modules */ -# define LM3S_NI2C 2 /* Two I2C modules */ -# define LM3S_NADC 1 /* One ADC module */ -# define LM2S_NPWM 3 /* Three PWM generator modules */ -# define LM3S_NQEI 2 /* Two quadrature encoders */ -# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ -#elif defined(CONFIG_ARCH_CHIP_LM3S9B96) -# define LM3S_NTIMERS 4 /* Four general purpose timers */ -# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ -# undef LM3S_ETHTS /* No timestamp register */ -# define LM3S_NSSI 2 /* Two SSI modules */ -# define LM3S_NUARTS 3 /* Three UART modules */ -# define LM3S_NI2C 2 /* Two I2C modules */ -# define LM3S_NADC 2 /* Two ADC module */ -# define LM3S_CAN 2 /* Two CAN module */ -# define LM3S_NPWM 4 /* Four PWM generator modules */ -# define LM3S_NQEI 2 /* Two quadrature encoders */ -# define LM3S_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */ -#elif defined(CONFIG_ARCH_CHIP_LM3S8962) -# define LM3S_NTIMERS 4 /* Four general purpose timers */ -# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */ -# define LM3S_NSSI 1 /* One SSI module */ -# define LM3S_NUARTS 3 /* Two UART modules */ -# define LM3S_NI2C 2 /* One I2C module */ -# define LM3S_NADC 1 /* One ADC module */ -# define LM2S_NPWM 3 /* Three PWM generator modules */ -# define LM3S_NQEI 2 /* Two quadrature encoders */ -# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */ -# define LC3S_CANCONTROLLER 1 /* One CAN controller */ -#else -# error "Capabilities not specified for this LM3S chip" -#endif - /* Then get all of the register definitions */ -#include "lm3s_memorymap.h" /* Memory map */ -#include "lm3s_syscontrol.h" /* System control module */ -#include "lm3s_gpio.h" /* GPIO modules */ -#include "lm3s_uart.h" /* UART modules */ -#include "lm3s_i2c.h" /* I2C modules */ -#include "lm3s_ssi.h" /* SSI modules */ -#include "lm3s_ethernet.h" /* Ethernet MAC and PHY */ -#include "lm3s_flash.h" /* FLASH */ +#include "chip/lm_memorymap.h" /* Memory map */ +#include "chip/lm3s_syscontrol.h" /* System control module */ +#include "chip/lm3s_gpio.h" /* GPIO modules */ +#include "chip/lm3s_uart.h" /* UART modules */ +#include "chip/lm3s_i2c.h" /* I2C modules */ +#include "chip/lm3s_ssi.h" /* SSI modules */ +#include "chip/lm3s_ethernet.h" /* Ethernet MAC and PHY */ +#include "chip/lm3s_flash.h" /* FLASH */ /************************************************************************************ * Public Types diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h new file mode 100644 index 000000000..5b54d44ac --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h @@ -0,0 +1,113 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_epi.h + * + * Copyright (C) 2009-2013 Max Neklyudov. All rights reserved. + * Author: Max Neklyudov + * + * 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_CHIP_LM3S_EPI_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_EPI_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* External Peripheral Interface Register Offsets ***********************************/ + +#define LM3S_EPI_CFG_OFFSET 0x000 +#define LM3S_EPI_SDRAMCFG_OFFSET 0x010 +#define LM3S_EPI_ADDRMAP_OFFSET 0x01C +#define LM3S_EPI_STAT_OFFSET 0x060 +#define LM3S_EPI_BAUD_OFFSET 0x004 + +/* External Peripheral Interface Register Addresses *********************************/ + +#define LM3S_EPI0_CFG (LM3S_EPI0_BASE + LM3S_EPI_CFG_OFFSET) +#define LM3S_EPI0_SDRAMCFG (LM3S_EPI0_BASE + LM3S_EPI_SDRAMCFG_OFFSET) +#define LM3S_EPI0_ADDRMAP (LM3S_EPI0_BASE + LM3S_EPI_ADDRMAP_OFFSET) +#define LM3S_EPI0_STAT (LM3S_EPI0_BASE + LM3S_EPI_STAT_OFFSET) +#define LM3S_EPI0_BAUD (LM3S_EPI0_BASE + LM3S_EPI_BAUD_OFFSET) + +/* External Peripheral Interface Register Bit Definitions ***************************/ + +/* EPI Configuration (EPICFG), offset 0x000 */ + +#define EPI_CFG_MODE_SHIFT 0 /* Bits 3-0: Mode Select */ +#define EPI_CFG_MODE_MASK (0x1f << EPI_CFG_MODE_SHIFT) +# define EPI_CFG_MODE_SDRAM (0x11 << EPI_CFG_MODE_SHIFT) /* SDRAM + BLKEN */ + +/* EPI Address Map (EPIADDRMAP), offset 0x01C */ + +#define EPI_ADDRMAP_ERADR_SHIFT 0 /* Bits 1-0: External RAM Address */ +#define EPI_ADDRMAP_ERADR_MASK (0x3 << EPI_ADDRMAP_ERADR_SHIFT) +# define EPI_ADDRMAP_ERADR_6 (0x1 << EPI_ADDRMAP_ERADR_SHIFT) +# define EPI_ADDRMAP_ERADR_8 (0x2 << EPI_ADDRMAP_ERADR_SHIFT) +#define EPI_ADDRMAP_ERSZ_SHIFT 2 /* Bits 3-2: External RAM Size */ +#define EPI_ADDRMAP_ERSZ_MASK (0x3 << EPI_ADDRMAP_ERSZ_SHIFT) +# define EPI_ADDRMAP_ERSZ_256B (0x0 << EPI_ADDRMAP_ERSZ_SHIFT) +# define EPI_ADDRMAP_ERSZ_64KB (0x1 << EPI_ADDRMAP_ERSZ_SHIFT) +# define EPI_ADDRMAP_ERSZ_16MB (0x2 << EPI_ADDRMAP_ERSZ_SHIFT) +# define EPI_ADDRMAP_ERSZ_512MB (0x3 << EPI_ADDRMAP_ERSZ_SHIFT) + +/* EPI Status (EPISTAT), offset 0x060 */ + +#define EPI_STAT_INITSEQ_SHIFT 6 /* Bits 6: Initialization Sequence */ +#define EPI_STAT_INITSEQ_MASK (0x1 << EPI_STAT_INITSEQ_SHIFT) + +/* EPI SDRAM Configuration (EPISDRAMCFG), offset 0x010 */ + +#define EPI_SDRAMCFG_SIZE_SHIFT 0 /* Bits 1-0: Size of SDRAM */ +#define EPI_SDRAMCFG_SIZE_MASK (3 << EPI_SDRAMCFG_SIZE_SHIFT) +# define EPI_SDRAMCFG_SIZE_8MB (0x0 << EPI_SDRAMCFG_SIZE_SHIFT) +# define EPI_SDRAMCFG_SIZE_16MB (0x1 << EPI_SDRAMCFG_SIZE_SHIFT) +# define EPI_SDRAMCFG_SIZE_32MB (0x2 << EPI_SDRAMCFG_SIZE_SHIFT) +# define EPI_SDRAMCFG_SIZE_64MB (0x3 << EPI_SDRAMCFG_SIZE_SHIFT) +#define EPI_SDRAMCFG_RFSH_SHIFT 16 /* Bits 26-16: Refresh Counter */ +#define EPI_SDRAMCFG_RFSH_MASK (0x7FF << EPI_SDRAMCFG_RFSH_SHIFT) +# define EPI_SDRAMCFG_RFSH(n) ((n) << EPI_SDRAMCFG_RFSH_SHIFT) +#define EPI_SDRAMCFG_FREQ_SHIFT 30 /* EPI Frequency Range */ +#define EPI_SDRAMCFG_FREQ_MASK (3 << EPI_SDRAMCFG_FREQ_SHIFT) +# define EPI_SDRAMCFG_FREQ_0_15MHZ (0x0 << EPI_SDRAMCFG_FREQ_SHIFT) +# define EPI_SDRAMCFG_FREQ_15_30MHZ (0x1 << EPI_SDRAMCFG_FREQ_SHIFT) +# define EPI_SDRAMCFG_FREQ_30_50MHZ (0x2 << EPI_SDRAMCFG_FREQ_SHIFT) +# define EPI_SDRAMCFG_FREQ_50_100MHZ (0x3 << EPI_SDRAMCFG_FREQ_SHIFT) + +/* EPI Main Baud Rate (EPIBAUD), offset 0x004 */ + +#define EPI_BAUD_COUNT0_SHIFT 0 +#define EPI_BAUD_COUNT0_MASK (0xFFFF << EPI_BAUD_COUNT0_SHIFT) +# define EPI_BAUD_COUNT0(n) ((n) << EPI_BAUD_COUNT0_SHIFT) + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_EPI_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h new file mode 100644 index 000000000..940686e7d --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h @@ -0,0 +1,203 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_ethernet.h + * + * Copyright (C) 2009-2010, 2012-2013 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_CHIP_LM3S_ETHERNET_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_ETHERNET_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Ethernet Controller Register Offsets *********************************************/ + +/* Ethernet MAC Register Offsets */ + +#define LM3S_MAC_RIS_OFFSET 0x000 /* Ethernet MAC Raw Interrupt Status */ +#define LM3S_MAC_IACK_OFFSET 0x000 /* Ethernet MAC Acknowledge */ +#define LM3S_MAC_IM_OFFSET 0x004 /* Ethernet MAC Interrupt Mask */ +#define LM3S_MAC_RCTL_OFFSET 0x008 /* Ethernet MAC Receive Control */ +#define LM3S_MAC_TCTL_OFFSET 0x00c /* Ethernet MAC Transmit Control */ +#define LM3S_MAC_DATA_OFFSET 0x010 /* Ethernet MAC Data */ +#define LM3S_MAC_IA0_OFFSET 0x014 /* Ethernet MAC Individual Address 0 */ +#define LM3S_MAC_IA1_OFFSET 0x018 /* Ethernet MAC Individual Address 1 */ +#define LM3S_MAC_THR_OFFSET 0x01c /* Ethernet MAC Threshold */ +#define LM3S_MAC_MCTL_OFFSET 0x020 /* Ethernet MAC Management Control */ +#define LM3S_MAC_MDV_OFFSET 0x024 /* Ethernet MAC Management Divider */ +#define LM3S_MAC_MTXD_OFFSET 0x02c /* Ethernet MAC Management Transmit Data */ +#define LM3S_MAC_MRXD_OFFSET 0x030 /* Ethernet MAC Management Receive Data */ +#define LM3S_MAC_NP_OFFSET 0x034 /* Ethernet MAC Number of Packets */ +#define LM3S_MAC_TR_OFFSET 0x038 /* Ethernet MAC Transmission Request */ +#ifdef LM3S_ETHTS +# define LM3S_MAC_TS_OFFSET 0x03c /* Ethernet MAC Time Stamp Configuration */ +#endif + +/* MII Management Register Offsets (see include/nuttx/net/mii.h) */ + +/* Ethernet Controller Register Addresses *******************************************/ + +#define LM3S_MAC_RIS (LM3S_ETHCON_BASE + LM3S_MAC_RIS_OFFSET) +#define LM3S_MAC_IACK (LM3S_ETHCON_BASE + LM3S_MAC_IACK_OFFSET) +#define LM3S_MAC_IM (LM3S_ETHCON_BASE + LM3S_MAC_IM_OFFSET) +#define LM3S_MAC_RCTL (LM3S_ETHCON_BASE + LM3S_MAC_RCTL_OFFSET) +#define LM3S_MAC_TCTL (LM3S_ETHCON_BASE + LM3S_MAC_TCTL_OFFSET) +#define LM3S_MAC_DATA (LM3S_ETHCON_BASE + LM3S_MAC_DATA_OFFSET) +#define LM3S_MAC_IA0 (LM3S_ETHCON_BASE + LM3S_MAC_IA0_OFFSET) +#define LM3S_MAC_IA1 (LM3S_ETHCON_BASE + LM3S_MAC_IA1_OFFSET) +#define LM3S_MAC_THR (LM3S_ETHCON_BASE + LM3S_MAC_THR_OFFSET) +#define LM3S_MAC_MCTL (LM3S_ETHCON_BASE + LM3S_MAC_MCTL_OFFSET) +#define LM3S_MAC_MDV (LM3S_ETHCON_BASE + LM3S_MAC_MDV_OFFSET) +#define LM3S_MAC_MTXD (LM3S_ETHCON_BASE + LM3S_MAC_MTXD_OFFSET) +#define LM3S_MAC_MRXD (LM3S_ETHCON_BASE + LM3S_MAC_MRXD_OFFSET) +#define LM3S_MAC_NP (LM3S_ETHCON_BASE + LM3S_MAC_NP_OFFSET) +#define LM3S_MAC_TR (LM3S_ETHCON_BASE + LM3S_MAC_TR_OFFSET) +#ifdef LM3S_ETHTS +# define LM3S_MAC_TS (LM3S_ETHCON_BASE + LM3S_MAC_TS_OFFSET) +#endif + +/* Memory Mapped MII Management Registers */ + +#define MAC_MII_MCR (LM3S_ETHCON_BASE + MII_MCR) +#define MAC_MII_MSR (LM3S_ETHCON_BASE + MII_MSR) +#define MAC_MII_PHYID1 (LM3S_ETHCON_BASE + MII_PHYID1) +#define MAC_MII_PHYID2 (LM3S_ETHCON_BASE + MII_PHYID2) +#define MAC_MII_ADVERTISE (LM3S_ETHCON_BASE + MII_ADVERTISE) +#define MAC_MII_LPA (LM3S_ETHCON_BASE + MII_LPA) +#define MAC_MII_EXPANSION (LM3S_ETHCON_BASE + MII_EXPANSION) +#define MAC_MII_VSPECIFIC (LM3S_ETHCON_BASE + MII_LM3S_VSPECIFIC) +#define MAC_MII_INTCS (LM3S_ETHCON_BASE + MII_LM3S_INTCS) +#define MAC_MII_DIAGNOSTIC (LM3S_ETHCON_BASE + MII_LM3S_DIAGNOSTIC) +#define MAC_MII_XCVRCONTROL (LM3S_ETHCON_BASE + MII_LM3S_XCVRCONTROL) +#define MAC_MII_LEDCONFIG (LM3S_ETHCON_BASE + MII_LM3S_LEDCONFIG) +#define MAC_MII_MDICONTROL (LM3S_ETHCON_BASE + MII_LM3S_MDICONTROL) + +/* Ethernet Controller Register Bit Definitions *************************************/ + +/* Ethernet MAC Raw Interrupt Status/Acknowledge (MACRIS/MACIACK), offset 0x000 */ + +#define MAC_RIS_RXINT (1 << 0) /* Bit 0: Packet Received */ +#define MAC_RIS_TXER (1 << 1) /* Bit 1: Transmit Error */ +#define MAC_RIS_TXEMP (1 << 2) /* Bit 2: Transmit FIFO Empty */ +#define MAC_RIS_FOV (1 << 3) /* Bit 3: FIFO Overrun */ +#define MAC_RIS_RXER (1 << 4) /* Bit 4: Receive Error */ +#define MAC_RIS_MDINT (1 << 5) /* Bit 5: MII Transaction Complete */ +#define MAC_RIS_PHYINT (1 << 6) /* Bit 6: PHY Interrupt */ + +#define MAC_IACK_RXINT (1 << 0) /* Bit 0: Clear Packet Received */ +#define MAC_IACK_TXER (1 << 1) /* Bit 1: Clear Transmit Error */ +#define MAC_IACK_TXEMP (1 << 2) /* Bit 2: Clear Transmit FIFO Empty */ +#define MAC_IACK_FOV (1 << 3) /* Bit 3: Clear FIFO Overrun */ +#define MAC_IACK_RXER (1 << 4) /* Bit 4: Clear Receive Error */ +#define MAC_IACK_MDINT (1 << 5) /* Bit 5: Clear MII Transaction Complete */ +#define MAC_IACK_PHYINT (1 << 6) /* Bit 6: Clear PHY Interrupt */ + +/* Ethernet MAC Interrupt Mask (MACIM), offset 0x004 */ + +#define MAC_IM_RXINTM (1 << 0) /* Bit 0: Mask Packet Received */ +#define MAC_IM_TXERM (1 << 1) /* Bit 1: Mask Transmit Error */ +#define MAC_IM_TXEMPM (1 << 2) /* Bit 2: Mask Transmit FIFO Empty */ +#define MAC_IM_FOVM (1 << 3) /* Bit 3: Mask FIFO Overrun */ +#define MAC_IM_RXERM (1 << 4) /* Bit 4: Mask Receive Error */ +#define MAC_IM_MDINTM (1 << 5) /* Bit 5: Mask MII Transaction Complete */ +#define MAC_IM_PHYINTM (1 << 6) /* Bit 6: Mask PHY Interrupt */ +#define MAC_IM_ALLINTS 0x7f + +/* Ethernet MAC Receive Control (MACRCTL), offset 0x008 */ + +#define MAC_RCTL_RXEN (1 << 0) /* Bit 0: Enable Receiver */ +#define MAC_RCTL_AMUL (1 << 1) /* Bit 1: Enable Multicast Frames */ +#define MAC_RCTL_PRMS (1 << 2) /* Bit 2: Enable Promiscuous Mode */ +#define MAC_RCTL_BADCRC (1 << 3) /* Bit 3: Enable Reject Bad CRC */ +#define MAC_RCTL_RSTFIFO (1 << 4) /* Bit 4: Clear Receive FIFO */ + +/* Ethernet MAC Transmit Control (MACTCTL), offset 0x00c */ + +#define MAC_TCTL_TXEN (1 << 0) /* Bit 0: Enable Transmitter */ +#define MAC_TCTL_PADEN (1 << 1) /* Bit 1: Enable Packet Padding */ +#define MAC_TCTL_CRC (1 << 2) /* Bit 2: Enable CRC Generation */ +#define MAC_TCTL_DUPLEX (1 << 4) /* Bit 4: Enable Duplex Mode */ + +/* Ethernet MAC Threshold (MACTHR), offset 0x01c */ + +#define MAC_THR_MASK 0x3f /* Bits 5-0: Threshold Value */ + +/* Ethernet MAC Management Control (MACMCTL), offset 0x020 */ + +#define MAC_MCTL_START (1 << 0) /* Bit 0: MII Register Transaction Enable */ +#define MAC_MCTL_WRITE (1 << 1) /* Bit 1: MII Register Transaction Type */ +#define MAC_MCTL_REGADR_SHIFT 3 /* Bits 7-3: MII Register Address */ +#define MAC_MCTL_REGADR_MASK (0x1f << MAC_MCTL_REGADR_SHIFT) + +/* Ethernet MAC Management Divider (MACMDV), offset 0x024 */ + +#define MAC_MDV_MASK 0xff /* Bits 7-0: Clock Divider */ + +/* Ethernet MAC Management Transmit Data (MACTXD), offset 0x02c */ + +#define MAC_MTXD_MASK 0xffff /* Bits 15-0: MII Register Transmit Data */ + +/* Ethernet MAC Management Receive Data (MACRXD), offset 0x030 */ + +#define MAC_MTRD_MASK 0xffff /* Bits 15-0: MII Register Receive Data */ + +/* Ethernet MAC Number of Packets (MACNP), offset 0x034 */ + +#define MAC_NP_MASK 0x3f /* Bits 5-0: Number of Packets in Receive FIFO */ + +/* Ethernet MAC Transmission Request (MACTR), offset 0x038 */ + +#define MAC_TR_NEWTX (1 << 0) /* Bit 0: New Transmission */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_ETHERNET_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h new file mode 100644 index 000000000..2bd8956b0 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h @@ -0,0 +1,128 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_flash.h + * + * Copyright (C) 2009, 2013 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_CHIP_LM3S_FLASH_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_FLASH_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* FLASH register offsets ***********************************************************/ + +/* The FMA, FMD, FMC, FCRIS, FCIM, and FCMISC registers are relative to the Flash + * control base address of LM3S_FLASHCON_BASE. + */ + +#define LM3S_FLASH_FMA_OFFSET 0x000 /* Flash memory address */ +#define LM3S_FLASH_FMD_OFFSET 0x004 /* Flash memory data */ +#define LM3S_FLASH_FMC_OFFSET 0x008 /* Flash memory control */ +#define LM3S_FLASH_FCRIS_OFFSET 0x00c /* Flash controller raw interrupt status */ +#define LM3S_FLASH_FCIM_OFFSET 0x010 /* Flash controller interrupt mask */ +#define LM3S_FLASH_FCMISC_OFFSET 0x014 /* Flash controller masked interrupt status and clear */ */ + +/* The FMPREn, FMPPEn, USECRL, USER_DBG, and USER_REGn registers are relative to the + * System Control base address of LM3S_SYSCON_BASE + */ + +#define LM3S_FLASH_FMPRE_OFFSET 0x130 /* Flash memory protection read enable */ +#define LM3S_FLASH_FMPPE_OFFSET 0x134 /* Flash memory protection program enable */ +#define LM3S_FLASH_USECRL_OFFSET 0x140 /* USec Reload */ +#define LM3S_FLASH_USERDBG_OFFSET 0x1d0 /* User Debug */ +#define LM3S_FLASH_USERREG0_OFFSET 0x1e0 /* User Register 0 */ +#define LM3S_FLASH_USERREG1_OFFSET 0x1e4 /* User Register 1 */ +#define LM3S_FLASH_FMPRE0_OFFSET 0x200 /* Flash Memory Protection Read Enable 0 */ +#define LM3S_FLASH_FMPRE1_OFFSET 0x204 /* Flash Memory Protection Read Enable 1 */ +#define LM3S_FLASH_FMPRE2_OFFSET 0x208 /* Flash Memory Protection Read Enable 2 */ +#define LM3S_FLASH_FMPRE3_OFFSET 0x20c /* Flash Memory Protection Read Enable 3 */ +#define LM3S_FLASH_FMPPE0_OFFSET 0x400 /* Flash Memory Protection Program Enable 0 */ +#define LM3S_FLASH_FMPPE1_OFFSET 0x404 /* Flash Memory Protection Program Enable 1 */ +#define LM3S_FLASH_FMPPE2_OFFSET 0x408 /* Flash Memory Protection Program Enable 2 */ +#define LM3S_FLASH_FMPPE3_OFFSET 0x40c /* Flash Memory Protection Program Enable 3 */ + +/* FLASH register addresses *********************************************************/ + +/* The FMA, FMD, FMC, FCRIS, FCIM, and FCMISC registers are relative to the Flash + * control base address of LM3S_FLASHCON_BASE. + */ + +#define LM3S_FLASH_FMA (LM3S_FLASHCON_BASE + LM3S_FLASH_FMA_OFFSET) +#define LM3S_FLASH_FMD (LM3S_FLASHCON_BASE + LM3S_FLASH_FMD_OFFSET) +#define LM3S_FLASH_FMC (LM3S_FLASHCON_BASE + LM3S_FLASH_FMC_OFFSET) +#define LM3S_FLASH_FCRIS (LM3S_FLASHCON_BASE + LM3S_FLASH_FCRIS_OFFSET) +#define LM3S_FLASH_FCIM (LM3S_FLASHCON_BASE + LM3S_FLASH_FCIM_OFFSET) +#define LM3S_FLASH_FCMISC (LM3S_FLASHCON_BASE + LM3S_FLASH_FCMISC_OFFSET) + +/* The FMPREn, FMPPEn, USECRL, USER_DBG, and USER_REGn registers are relative to the + * System Control base address of LM3S_SYSCON_BASE + */ + +#define LM3S_FLASH_FMPRE (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE_OFFSET) +#define LM3S_FLASH_FMPPE (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE_OFFSET) +#define LM3S_FLASH_USECRL (LM3S_SYSCON_BASE + LM3S_FLASH_USECRL_OFFSET) +#define LM3S_FLASH_USERDBG (LM3S_SYSCON_BASE + LM3S_FLASH_USERDBG_OFFSET) +#define LM3S_FLASH_USERREG0 (LM3S_SYSCON_BASE + LM3S_FLASH_USERREG0_OFFSET) +#define LM3S_FLASH_USERREG1 (LM3S_SYSCON_BASE + LM3S_FLASH_USERREG1_OFFSET) +#define LM3S_FLASH_FMPRE0 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE0_OFFSET) +#define LM3S_FLASH_FMPRE1 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE1_OFFSET) +#define LM3S_FLASH_FMPRE2 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE2_OFFSET) +#define LM3S_FLASH_FMPRE3 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE3_OFFSET) +#define LM3S_FLASH_FMPPE0 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE0_OFFSET) +#define LM3S_FLASH_FMPPE1 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE1_OFFSET) +#define LM3S_FLASH_FMPPE2 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE2_OFFSET) +#define LM3S_FLASH_FMPPE3 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE3_OFFSET) + +/* FLASH register bit defitiions ****************************************************/ +/* To be provided */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_FLASH_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h new file mode 100644 index 000000000..7253c1e7a --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h @@ -0,0 +1,395 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_gpio.h + * + * Copyright (C) 2009-2010, 2013 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_CHIP_LM3S_GPIO_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_GPIO_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* GPIO Register Offsets ************************************************************/ + +#define LM3S_GPIO_DATA_OFFSET 0x000 /* GPIO Data */ +#define LM3S_GPIO_DIR_OFFSET 0x400 /* GPIO Direction */ +#define LM3S_GPIO_IS_OFFSET 0x404 /* GPIO Interrupt Sense */ +#define LM3S_GPIO_IBE_OFFSET 0x408 /* GPIO Interrupt Both Edges */ +#define LM3S_GPIO_IEV_OFFSET 0x40c /* GPIO Interrupt Event */ +#define LM3S_GPIO_IM_OFFSET 0x410 /* GPIO Interrupt Mask */ +#define LM3S_GPIO_RIS_OFFSET 0x414 /* GPIO Raw Interrupt Status */ +#define LM3S_GPIO_MIS_OFFSET 0x418 /* GPIO Masked Interrupt Status */ +#define LM3S_GPIO_ICR_OFFSET 0x41c /* GPIO Interrupt Clear */ +#define LM3S_GPIO_AFSEL_OFFSET 0x420 /* GPIO Alternate Function */ +#define LM3S_GPIO_DR2R_OFFSET 0x500 /* Select GPIO 2-mA Drive Select */ +#define LM3S_GPIO_DR4R_OFFSET 0x504 /* GPIO 4-mA Drive Select */ +#define LM3S_GPIO_DR8R_OFFSET 0x508 /* GPIO 8-mA Drive Select */ +#define LM3S_GPIO_ODR_OFFSET 0x50c /* GPIO Open Drain Select */ +#define LM3S_GPIO_PUR_OFFSET 0x510 /* GPIO Pull-Up Select */ +#define LM3S_GPIO_PDR_OFFSET 0x514 /* GPIO Pull-Down Select */ +#define LM3S_GPIO_SLR_OFFSET 0x518 /* GPIO Slew Rate Control Select */ +#define LM3S_GPIO_DEN_OFFSET 0x51C /* GPIO Digital Enable */ +#define LM3S_GPIO_LOCK_OFFSET 0x520 /* GPIO Lock */ +#define LM3S_GPIO_CR_OFFSET 0x524 /* GPIO Commit */ +#define LM3S_GPIO_PERIPHID4_OFFSET 0xfd0 /* GPIO Peripheral Identification 4 */ +#define LM3S_GPIO_PERIPHID5_OFFSET 0xfd4 /* GPIO Peripheral Identification 5 */ +#define LM3S_GPIO_PERIPHID6_OFFSET 0xfd8 /* GPIO Peripheral Identification 6 */ +#define LM3S_GPIO_PERIPHID7_OFFSET 0xfdc /* GPIO Peripheral Identification 7 */ +#define LM3S_GPIO_PERIPHID0_OFFSET 0xfe0 /* GPIO Peripheral Identification 0 */ +#define LM3S_GPIO_PERIPHID1_OFFSET 0xfe4 /* GPIO Peripheral Identification 1 */ +#define LM3S_GPIO_PERIPHID2_OFFSET 0xfe8 /* GPIO Peripheral Identification 2 */ +#define LM3S_GPIO_PERIPHID3_OFFSET 0xfec /* GPIO Peripheral Identification 3 */ +#define LM3S_GPIO_PCELLID0_OFFSET 0xff0 /* GPIO PrimeCell Identification 0 */ +#define LM3S_GPIO_PCELLID1_OFFSET 0xff4 /* GPIO PrimeCell Identification 1 */ +#define LM3S_GPIO_PCELLID2_OFFSET 0xff8 /* GPIO PrimeCell Identification 2 */ +#define LM3S_GPIO_PCELLID3_OFFSET 0xffc /* GPIO PrimeCell Identification 3*/ + +/* GPIO Register Addresses **********************************************************/ + +#define LM3S_GPIOA_DATA (LM3S_GPIOA_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOA_DIR (LM3S_GPIOA_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOA_IS (LM3S_GPIOA_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOA_IBE (LM3S_GPIOA_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOA_IEV (LM3S_GPIOA_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOA_IM (LM3S_GPIOA_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOA_RIS (LM3S_GPIOA_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOA_MIS (LM3S_GPIOA_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOA_ICR (LM3S_GPIOA_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOA_AFSEL (LM3S_GPIOA_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOA_DR2R (LM3S_GPIOA_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOA_DR4R (LM3S_GPIOA_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOA_DR8R (LM3S_GPIOA_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOA_ODR (LM3S_GPIOA_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOA_PUR (LM3S_GPIOA_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOA_PDR (LM3S_GPIOA_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOA_SLR (LM3S_GPIOA_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOA_DEN (LM3S_GPIOA_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOA_LOCK (LM3S_GPIOA_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOA_CR (LM3S_GPIOA_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOA_PERIPHID4 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOA_PERIPHID5 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOA_PERIPHID6 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOA_PERIPHID7 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOA_PERIPHID0 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOA_PERIPHID1 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOA_PERIPHID2 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOA_PERIPHID3 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOA_PCELLID0 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOA_PCELLID1 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOA_PCELLID2 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOA_PCELLID3 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOB_DATA (LM3S_GPIOB_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOB_DIR (LM3S_GPIOB_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOB_IS (LM3S_GPIOB_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOB_IBE (LM3S_GPIOB_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOB_IEV (LM3S_GPIOB_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOB_IM (LM3S_GPIOB_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOB_RIS (LM3S_GPIOB_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOB_MIS (LM3S_GPIOB_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOB_ICR (LM3S_GPIOB_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOB_AFSEL (LM3S_GPIOB_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOB_DR2R (LM3S_GPIOB_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOB_DR4R (LM3S_GPIOB_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOB_DR8R (LM3S_GPIOB_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOB_ODR (LM3S_GPIOB_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOB_PUR (LM3S_GPIOB_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOB_PDR (LM3S_GPIOB_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOB_SLR (LM3S_GPIOB_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOB_DEN (LM3S_GPIOB_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOB_LOCK (LM3S_GPIOB_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOB_CR (LM3S_GPIOB_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOB_PERIPHID4 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOB_PERIPHID5 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOB_PERIPHID6 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOB_PERIPHID7 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOB_PERIPHID0 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOB_PERIPHID1 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOB_PERIPHID2 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOB_PERIPHID3 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOB_PCELLID0 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOB_PCELLID1 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOB_PCELLID2 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOB_PCELLID3 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOC_DATA (LM3S_GPIOC_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOC_DIR (LM3S_GPIOC_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOC_IS (LM3S_GPIOC_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOC_IBE (LM3S_GPIOC_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOC_IEV (LM3S_GPIOC_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOC_IM (LM3S_GPIOC_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOC_RIS (LM3S_GPIOC_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOC_MIS (LM3S_GPIOC_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOC_ICR (LM3S_GPIOC_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOC_AFSEL (LM3S_GPIOC_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOC_DR2R (LM3S_GPIOC_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOC_DR4R (LM3S_GPIOC_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOC_DR8R (LM3S_GPIOC_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOC_ODR (LM3S_GPIOC_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOC_PUR (LM3S_GPIOC_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOC_PDR (LM3S_GPIOC_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOC_SLR (LM3S_GPIOC_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOC_DEN (LM3S_GPIOC_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOC_LOCK (LM3S_GPIOC_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOC_CR (LM3S_GPIOC_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOC_PERIPHID4 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOC_PERIPHID5 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOC_PERIPHID6 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOC_PERIPHID7 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOC_PERIPHID0 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOC_PERIPHID1 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOC_PERIPHID2 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOC_PERIPHID3 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOC_PCELLID0 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOC_PCELLID1 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOC_PCELLID2 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOC_PCELLID3 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOD_DATA (LM3S_GPIOD_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOD_DIR (LM3S_GPIOD_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOD_IS (LM3S_GPIOD_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOD_IBE (LM3S_GPIOD_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOD_IEV (LM3S_GPIOD_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOD_IM (LM3S_GPIOD_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOD_RIS (LM3S_GPIOD_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOD_MIS (LM3S_GPIOD_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOD_ICR (LM3S_GPIOD_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOD_AFSEL (LM3S_GPIOD_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOD_DR2R (LM3S_GPIOD_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOD_DR4R (LM3S_GPIOD_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOD_DR8R (LM3S_GPIOD_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOD_ODR (LM3S_GPIOD_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOD_PUR (LM3S_GPIOD_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOD_PDR (LM3S_GPIOD_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOD_SLR (LM3S_GPIOD_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOD_DEN (LM3S_GPIOD_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOD_LOCK (LM3S_GPIOD_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOD_CR (LM3S_GPIOD_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOD_PERIPHID4 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOD_PERIPHID5 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOD_PERIPHID6 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOD_PERIPHID7 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOD_PERIPHID0 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOD_PERIPHID1 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOD_PERIPHID2 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOD_PERIPHID3 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOD_PCELLID0 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOD_PCELLID1 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOD_PCELLID2 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOD_PCELLID3 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOE_DATA (LM3S_GPIOE_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOE_DIR (LM3S_GPIOE_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOE_IS (LM3S_GPIOE_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOE_IBE (LM3S_GPIOE_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOE_IEV (LM3S_GPIOE_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOE_IM (LM3S_GPIOE_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOE_RIS (LM3S_GPIOE_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOE_MIS (LM3S_GPIOE_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOE_ICR (LM3S_GPIOE_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOE_AFSEL (LM3S_GPIOE_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOE_DR2R (LM3S_GPIOE_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOE_DR4R (LM3S_GPIOE_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOE_DR8R (LM3S_GPIOE_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOE_ODR (LM3S_GPIOE_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOE_PUR (LM3S_GPIOE_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOE_PDR (LM3S_GPIOE_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOE_SLR (LM3S_GPIOE_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOE_DEN (LM3S_GPIOE_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOE_LOCK (LM3S_GPIOE_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOE_CR (LM3S_GPIOE_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOE_PERIPHID4 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOE_PERIPHID5 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOE_PERIPHID6 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOE_PERIPHID7 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOE_PERIPHID0 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOE_PERIPHID1 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOE_PERIPHID2 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOE_PERIPHID3 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOE_PCELLID0 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOE_PCELLID1 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOE_PCELLID2 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOE_PCELLID3 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOF_DATA (LM3S_GPIOF_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOF_DIR (LM3S_GPIOF_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOF_IS (LM3S_GPIOF_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOF_IBE (LM3S_GPIOF_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOF_IEV (LM3S_GPIOF_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOF_IM (LM3S_GPIOF_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOF_RIS (LM3S_GPIOF_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOF_MIS (LM3S_GPIOF_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOF_ICR (LM3S_GPIOF_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOF_AFSEL (LM3S_GPIOF_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOF_DR2R (LM3S_GPIOF_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOF_DR4R (LM3S_GPIOF_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOF_DR8R (LM3S_GPIOF_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOF_ODR (LM3S_GPIOF_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOF_PUR (LM3S_GPIOF_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOF_PDR (LM3S_GPIOF_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOF_SLR (LM3S_GPIOF_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOF_DEN (LM3S_GPIOF_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOF_LOCK (LM3S_GPIOF_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOF_CR (LM3S_GPIOF_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOF_PERIPHID4 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOF_PERIPHID5 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOF_PERIPHID6 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOF_PERIPHID7 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOF_PERIPHID0 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOF_PERIPHID1 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOF_PERIPHID2 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOF_PERIPHID3 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOF_PCELLID0 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOF_PCELLID1 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOF_PCELLID2 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOF_PCELLID3 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOG_DATA (LM3S_GPIOG_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOG_DIR (LM3S_GPIOG_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOG_IS (LM3S_GPIOG_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOG_IBE (LM3S_GPIOG_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOG_IEV (LM3S_GPIOG_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOG_IM (LM3S_GPIOG_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOG_RIS (LM3S_GPIOG_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOG_MIS (LM3S_GPIOG_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOG_ICR (LM3S_GPIOG_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOG_AFSEL (LM3S_GPIOG_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOG_DR2R (LM3S_GPIOG_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOG_DR4R (LM3S_GPIOG_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOG_DR8R (LM3S_GPIOG_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOG_ODR (LM3S_GPIOG_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOG_PUR (LM3S_GPIOG_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOG_PDR (LM3S_GPIOG_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOG_SLR (LM3S_GPIOG_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOG_DEN (LM3S_GPIOG_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOG_LOCK (LM3S_GPIOG_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOG_CR (LM3S_GPIOG_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOG_PERIPHID4 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOG_PERIPHID5 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOG_PERIPHID6 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOG_PERIPHID7 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOG_PERIPHID0 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOG_PERIPHID1 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOG_PERIPHID2 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOG_PERIPHID3 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOG_PCELLID0 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOG_PCELLID1 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOG_PCELLID2 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOG_PCELLID3 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOH_DATA (LM3S_GPIOH_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOH_DIR (LM3S_GPIOH_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOH_IS (LM3S_GPIOH_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOH_IBE (LM3S_GPIOH_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOH_IEV (LM3S_GPIOH_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOH_IM (LM3S_GPIOH_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOH_RIS (LM3S_GPIOH_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOH_MIS (LM3S_GPIOH_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOH_ICR (LM3S_GPIOH_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOH_AFSEL (LM3S_GPIOH_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOH_DR2R (LM3S_GPIOH_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOH_DR4R (LM3S_GPIOH_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOH_DR8R (LM3S_GPIOH_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOH_ODR (LM3S_GPIOH_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOH_PUR (LM3S_GPIOH_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOH_PDR (LM3S_GPIOH_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOH_SLR (LM3S_GPIOH_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOH_DEN (LM3S_GPIOH_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOH_LOCK (LM3S_GPIOH_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOH_CR (LM3S_GPIOH_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOH_PERIPHID4 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOH_PERIPHID5 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOH_PERIPHID6 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOH_PERIPHID7 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOH_PERIPHID0 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOH_PERIPHID1 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOH_PERIPHID2 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOH_PERIPHID3 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOH_PCELLID0 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOH_PCELLID1 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOH_PCELLID2 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOH_PCELLID3 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +#define LM3S_GPIOJ_DATA (LM3S_GPIOJ_BASE + LM3S_GPIO_DATA_OFFSET) +#define LM3S_GPIOJ_DIR (LM3S_GPIOJ_BASE + LM3S_GPIO_DIR_OFFSET) +#define LM3S_GPIOJ_IS (LM3S_GPIOJ_BASE + LM3S_GPIO_IS_OFFSET) +#define LM3S_GPIOJ_IBE (LM3S_GPIOJ_BASE + LM3S_GPIO_IBE_OFFSET) +#define LM3S_GPIOJ_IEV (LM3S_GPIOJ_BASE + LM3S_GPIO_IEV_OFFSET) +#define LM3S_GPIOJ_IM (LM3S_GPIOJ_BASE + LM3S_GPIO_IM_OFFSET) +#define LM3S_GPIOJ_RIS (LM3S_GPIOJ_BASE + LM3S_GPIO_RIS_OFFSET) +#define LM3S_GPIOJ_MIS (LM3S_GPIOJ_BASE + LM3S_GPIO_MIS_OFFSET) +#define LM3S_GPIOJ_ICR (LM3S_GPIOJ_BASE + LM3S_GPIO_ICR_OFFSET) +#define LM3S_GPIOJ_AFSEL (LM3S_GPIOJ_BASE + LM3S_GPIO_AFSEL_OFFSET) +#define LM3S_GPIOJ_DR2R (LM3S_GPIOJ_BASE + LM3S_GPIO_DR2R_OFFSET) +#define LM3S_GPIOJ_DR4R (LM3S_GPIOJ_BASE + LM3S_GPIO_DR4R_OFFSET) +#define LM3S_GPIOJ_DR8R (LM3S_GPIOJ_BASE + LM3S_GPIO_DR8R_OFFSET) +#define LM3S_GPIOJ_ODR (LM3S_GPIOJ_BASE + LM3S_GPIO_ODR_OFFSET) +#define LM3S_GPIOJ_PUR (LM3S_GPIOJ_BASE + LM3S_GPIO_PUR_OFFSET) +#define LM3S_GPIOJ_PDR (LM3S_GPIOJ_BASE + LM3S_GPIO_PDR_OFFSET) +#define LM3S_GPIOJ_SLR (LM3S_GPIOJ_BASE + LM3S_GPIO_SLR_OFFSET) +#define LM3S_GPIOJ_DEN (LM3S_GPIOJ_BASE + LM3S_GPIO_DEN_OFFSET) +#define LM3S_GPIOJ_LOCK (LM3S_GPIOJ_BASE + LM3S_GPIO_LOCK_OFFSET) +#define LM3S_GPIOJ_CR (LM3S_GPIOJ_BASE + LM3S_GPIO_CR_OFFSET) +#define LM3S_GPIOJ_PERIPHID4 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID4_OFFSET) +#define LM3S_GPIOJ_PERIPHID5 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID5_OFFSET) +#define LM3S_GPIOJ_PERIPHID6 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID6_OFFSET) +#define LM3S_GPIOJ_PERIPHID7 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID7_OFFSET) +#define LM3S_GPIOJ_PERIPHID0 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID0_OFFSET) +#define LM3S_GPIOJ_PERIPHID1 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID1_OFFSET) +#define LM3S_GPIOJ_PERIPHID2 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID2_OFFSET) +#define LM3S_GPIOJ_PERIPHID3 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID3_OFFSET) +#define LM3S_GPIOJ_PCELLID0 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID0_OFFSET) +#define LM3S_GPIOJ_PCELLID1 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID1_OFFSET) +#define LM3S_GPIOJ_PCELLID2 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID2_OFFSET) +#define LM3S_GPIOJ_PCELLID3 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID3_OFFSET) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_GPIO_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h new file mode 100644 index 000000000..71ebe8fcf --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h @@ -0,0 +1,247 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_i2c.h + * + * Copyright (C) 2009, 2013 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_CHIP_LM3S_I2C_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_I2C_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* I2C Register Offsets *************************************************************/ + +/* I2C Master */ + +#define LM3S_I2CM_SA_OFFSET 0x000 /* I2C Master Slave Address */ +#define LM3S_I2CM_CS_OFFSET 0x004 /* I2C Master Control/Status */ +#define LM3S_I2CM_DR_OFFSET 0x008 /* I2C Master Data */ +#define LM3S_I2CM_TPR_OFFSET 0x00c /* I2C Master Timer Period */ +#define LM3S_I2CM_IMR_OFFSET 0x010 /* I2C Master Interrupt Mask */ +#define LM3S_I2CM_RIS_OFFSET 0x014 /* I2C Master Raw Interrupt Status */ +#define LM3S_I2CM_MIS_OFFSET 0x018 /* I2C Master Masked Interrupt Status */ +#define LM3S_I2CM_ICR_OFFSET 0x01c /* I2C Master Interrupt Clear */ +#define LM3S_I2CM_CR_OFFSET 0x020 /* I2C Master Configuration */ + +/* I2C Slave */ + +#define LM3S_I2CS_OAR_OFFSET 0x000 /* I2C Slave Own Address */ +#define LM3S_I2CS_CSR_OFFSET 0x004 /* I2C Slave Control/Status */ +#define LM3S_I2CS_DR_OFFSET 0x008 /* I2C Slave Data */ +#define LM3S_I2CS_IMR_OFFSET 0x00c /* I2C Slave Interrupt Mask */ +#define LM3S_I2CS_RIS_OFFSET 0x010 /* I2C Slave Raw Interrupt Status */ +#define LM3S_I2CS_MIS_OFFSET 0x014 /* I2C Slave Masked Interrupt Status */ +#define LM3S_I2CS_ICR_OFFSET 0x018 /* I2C Slave Interrupt Clear */ + +/* I2C Register Addresses ***********************************************************/ + +#if LM3S_NI2C > 0 + +/* I2C Master */ + +#define LM3S_I2CM_BASE(n) (LM3S_I2CM0_BASE + (n)*0x1000) +#define LM3S_I2CM_SA(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_SA_OFFSET) +#define LM3S_I2CM_CS(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_CS_OFFSET) +#define LM3S_I2CM_DR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_DR_OFFSET) +#define LM3S_I2CM_TPR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_TPR_OFFSET) +#define LM3S_I2CM_IMR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_IMR_OFFSET) +#define LM3S_I2CM_RIS(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_RIS_OFFSET) +#define LM3S_I2CM_MIS(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_MIS_OFFSET) +#define LM3S_I2CM_ICR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_ICR_OFFSET) +#define LM3S_I2CM_CR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_CR_OFFSET) + +/* I2C Slave */ + +#define LM3S_I2CS_BASE(n) (LM3S_I2CS0_BASE + (n)*0x1000) +#define LM3S_I2CS_OAR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_OAR_OFFSET) +#define LM3S_I2CS_CSR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_CSR_OFFSET) +#define LM3S_I2CS_DR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_DR_OFFSET) +#define LM3S_I2CS_IMR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_IMR_OFFSET) +#define LM3S_I2CS_RIS(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_RIS_OFFSET) +#define LM3S_I2CS_MIS(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_MIS_OFFSET) +#define LM3S_I2CS_ICR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_ICR_OFFSET) + +/* I2C0 Master */ + +#define LM3S_I2CM0_SA (LM3S_I2CM0_BASE + LM3S_I2CM_SA_OFFSET) +#define LM3S_I2CM0_CS (LM3S_I2CM0_BASE + LM3S_I2CM_CS_OFFSET) +#define LM3S_I2CM0_DR (LM3S_I2CM0_BASE + LM3S_I2CM_DR_OFFSET) +#define LM3S_I2CM0_TPR (LM3S_I2CM0_BASE + LM3S_I2CM_TPR_OFFSET) +#define LM3S_I2CM0_IMR (LM3S_I2CM0_BASE + LM3S_I2CM_IMR_OFFSET) +#define LM3S_I2CM0_RIS (LM3S_I2CM0_BASE + LM3S_I2CM_RIS_OFFSET) +#define LM3S_I2CM0_MIS (LM3S_I2CM0_BASE + LM3S_I2CM_MIS_OFFSET) +#define LM3S_I2CM0_ICR (LM3S_I2CM0_BASE + LM3S_I2CM_ICR_OFFSET) +#define LM3S_I2CM0_CR (LM3S_I2CM0_BASE + LM3S_I2CM_CR_OFFSET) + +/* I2C0 Slave */ + +#define LM3S_I2CS0_OAR (LM3S_I2CS0_BASE + LM3S_I2CS_OAR_OFFSET) +#define LM3S_I2CS0_CSR (LM3S_I2CS0_BASE + LM3S_I2CS_CSR_OFFSET) +#define LM3S_I2CS0_DR (LM3S_I2CS0_BASE + LM3S_I2CS_DR_OFFSET) +#define LM3S_I2CS0_IMR (LM3S_I2CS0_BASE + LM3S_I2CS_IMR_OFFSET) +#define LM3S_I2CS0_RIS (LM3S_I2CS0_BASE + LM3S_I2CS_RIS_OFFSET) +#define LM3S_I2CS0_MIS (LM3S_I2CS0_BASE + LM3S_I2CS_MIS_OFFSET) +#define LM3S_I2CS0_ICR (LM3S_I2CS0_BASE + LM3S_I2CS_ICR_OFFSET) + +#if LM3S_NI2C > 1 + +/* I2C1 Master */ + +#define LM3S_I2CM1_SA (LM3S_I2CM1_BASE + LM3S_I2CM_SA_OFFSET) +#define LM3S_I2CM1_CS (LM3S_I2CM1_BASE + LM3S_I2CM_CS_OFFSET) +#define LM3S_I2CM1_DR (LM3S_I2CM1_BASE + LM3S_I2CM_DR_OFFSET) +#define LM3S_I2CM1_TPR (LM3S_I2CM1_BASE + LM3S_I2CM_TPR_OFFSET) +#define LM3S_I2CM1_IMR (LM3S_I2CM1_BASE + LM3S_I2CM_IMR_OFFSET) +#define LM3S_I2CM1_RIS (LM3S_I2CM1_BASE + LM3S_I2CM_RIS_OFFSET) +#define LM3S_I2CM1_MIS (LM3S_I2CM1_BASE + LM3S_I2CM_MIS_OFFSET) +#define LM3S_I2CM1_ICR (LM3S_I2CM1_BASE + LM3S_I2CM_ICR_OFFSET) +#define LM3S_I2CM1_CR (LM3S_I2CM1_BASE + LM3S_I2CM_CR_OFFSET) + +/* I2C1 Slave */ + +#define LM3S_I2CS1_OAR (LM3S_I2CS1_BASE + LM3S_I2CS_OAR_OFFSET) +#define LM3S_I2CS1_CSR (LM3S_I2CS1_BASE + LM3S_I2CS_CSR_OFFSET) +#define LM3S_I2CS1_DR (LM3S_I2CS1_BASE + LM3S_I2CS_DR_OFFSET) +#define LM3S_I2CS1_IMR (LM3S_I2CS1_BASE + LM3S_I2CS_IMR_OFFSET) +#define LM3S_I2CS1_RIS (LM3S_I2CS1_BASE + LM3S_I2CS_RIS_OFFSET) +#define LM3S_I2CS1_MIS (LM3S_I2CS1_BASE + LM3S_I2CS_MIS_OFFSET) +#define LM3S_I2CS1_ICR (LM3S_I2CS1_BASE + LM3S_I2CS_ICR_OFFSET) + +#endif +#endif + +/* I2C_Register Bit Definitions *****************************************************/ + +/* I2C Master Slave Address (I2CM_SA), offset 0x000 */ + +#define I2CM_SA_RS (1 << 0) /* Bit 0: Receive/Send */ +#define I2CM_SA_SA_SHIFT 1 /* Bits 7-1: I2C Slave Address */ +#define I2CM_SA_SA_MASK (0x7f << I2CM_SA_SA_SHIFT) + +/* I2C Master Control/Status (I2CM_CS), offset 0x004 */ + +#define I2CM_CS_BUSY (1 << 0) /* Bit 0: I2C Busy (read) */ +#define I2CM_CS_ERROR (1 << 1) /* Bit 1: Error in last bus operation (read) */ +#define I2CM_CS_ADRACK (1 << 2) /* Bit 2: Acknowledge Address (read) */ +#define I2CM_CS_DATACK (1 << 3) /* Bit 3: Acknowledge Data (read) */ +#define I2CM_CS_ARBLST (1 << 4) /* Bit 4: Arbitration Lost (read) */ +#define I2CM_CS_IDLE (1 << 5) /* Bit 5: I2C Idle (read) */ +#define I2CM_CS_BUSBSY (1 << 6) /* Bit 6: Bus Busy (read) */ + +#define I2CM_CS_RUN (1 << 0) /* Bit 0: I2C Master Enable (write) */ +#define I2CM_CS_START (1 << 1) /* Bit 1: Generate START (write) */ +#define I2CM_CS_STOP (1 << 2) /* Bit 2: Generate STOP (write) */ +#define I2CM_CS_ACK (1 << 3) /* Bit 3: Data Acknowledge Enable (write) */ + +/* I2C Master Data (I2CM_DR), offset 0x008 */ + +#define I2CM_DR_MASK 0xff /* Bits 7-0: Data transferred */ + +/* I2C Master Timer Period (I2CM_TPR), offset 0x00c */ + +#define I2CM_TPR_MASK 0xff /* Bits 7-0: SCL Clock Period */ + +/* I2C Master Interrupt Mask (I2CM_IMR), offset 0x010 */ + +#define I2CM_IMR_IM (1 << 0) /* Bit 0: Interrupt Mask */ + +/* I2C Master Raw Interrupt Status (I2CM_RIS), offset 0x014 */ + +#define I2CM_RIS_RIS (1 << 0) /* Bit 0: Raw Interrupt Status */ + +/* I2C Master Masked Interrupt Status (I2CM_MIS), offset 0x018 */ + +#define I2CM_MIS_MIS (1 << 0) /* Bit 0: Masked Interrupt Status */ + +/* I2C Master Masked Interrupt Status (I2CM_ICR), offset 0x01c */ + +#define I2CM_ICR_IC (1 << 0) /* Bit 0: Masked Interrupt Status */ + +/* I2C Master Configuration (I2CM_CR), offset 0x020 */ + +#define I2CM_CR_LPBK (1 << 0) /* Bit 0:: I2C Loopback */ +#define I2CM_CR_MFE (1 << 4 ) /* Bit 4: I2C Master Function Enable */ +#define I2CM_CR_SFE (1 << 5) /* Bit 5: I2C Slave Function Enable */ + +/* I2C Slave Own Address (I2CS_OAR), offset 0x000 */ + +#define I2CS_OAR_MASK 0xff /* Bits 7-0: I2C Slave Own Address */ + +/* I2C Slave Control/Status (I2CS_CSR), offset 0x004 */ + +#define I2CS_CSR_RREQ (1 << 0) /* Bit 0: Receive Request (read) */ +#define I2CS_CSR_TREQ (1 << 1) /* Bit 1: Transmit Request (read) */ +#define I2CS_CSR_FBR (1 << 2) /* Bit 2: First Byte Received (read) */ + +#define I2CS_CSR_DA (1 << 0) /* Bit 0: Device Active (write) */ + +/* I2C Slave Data (I2CS_DR), offset 0x008 */ + +#define I2CS_DR_MASK 0xff /* Bits 7-0: Data for Transfer */ + +/* I2C Slave Interrupt Mask (I2CS_IMR), offset 0x00c */ + +#define I2CM_IMR_DATAIM (1 << 0) /* Bit 0: Data Interrupt Mask */ + +/* I2C Slave Raw Interrupt Status (I2CS_RIS), offset 0x010 */ + +#define I2CM_RIS_DATARIS (1 << 0) /* Bit 0: Data Raw Interrupt Status */ + +/* I2C Slave Masked Interrupt Status (I2CS_MIS), offset 0x014 */ + +#define I2CM_MIS_DATAMIS (1 << 0) /* Bit 0: Data Masked Interrupt Status */ + +/* I2C Slave Interrupt Clear (I2CS_ICR), offset 0x018 */ + +#define I2CM_ICR_DATAIC (1 << 0) /* Bit 0: Data Interrupt Clear */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_I2C_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h new file mode 100644 index 000000000..31dc2b249 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h @@ -0,0 +1,360 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_memorymap.h + * + * Copyright (C) 2009-2010 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_CHIP_LM3S_MEMORYMAP_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Memory map ***********************************************************************/ + +#if defined(CONFIG_ARCH_CHIP_LM3S6918) || defined(CONFIG_ARCH_CHIP_LM3S6432) || \ + defined(CONFIG_ARCH_CHIP_LM3S6965) || defined(CONFIG_ARCH_CHIP_LM3S8962) +# define LM3S_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */ + /* -0x1fffffff: Reserved */ +# define LM3S_SRAM_BASE 0x20000000 /* -0x2000ffff: Bit-banded on-chip SRAM */ + /* -0x21ffffff: Reserved */ +# define LM3S_ASRAM_BASE 0x22000000 /* -0x221fffff: Bit-band alias of 20000000- */ + /* -0x3fffffff: Reserved */ +# 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 */ +# define LM3S_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */ +# define LM3S_FPB_BASE 0xe0002000 /* -0xe0002fff: Flash Patch and Breakpoint */ + /* -0xe000dfff: Reserved */ +# define LM3S_NVIC_BASE 0xe000e000 /* -0xe000efff: Nested Vectored Interrupt Controller */ + /* -0xe003ffff: Reserved */ +# define LM3S_TPIU_BASE 0xe0040000 /* -0xe0040fff: Trace Port Interface Unit */ + /* -0xffffffff: Reserved */ +#elif defined(CONFIG_ARCH_CHIP_LM3S9B96) +# define LM3S_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */ + /* -0x1fffffff: Reserved */ +# define LM3S_SRAM_BASE 0x20000000 /* -0x2000ffff: Bit-banded on-chip SRAM */ + /* -0x21ffffff: Reserved */ +# define LM3S_ASRAM_BASE 0x22000000 /* -0x221fffff: Bit-band alias of 20000000- */ + /* -0x3fffffff: Reserved */ +# define LM3S_PERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */ + /* -0x41ffffff: Peripherals */ +# define LM3S_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alise of 40000000- */ + /* -0x5fffffff: Reserved */ +# define LM3S_EPI0RAM_BASE 0x60000000 /* -0xDfffffff: EPI0 mapped peripheral and RAM */ +# define LM3S_ITM_BASE 0xe0000000 /* -0xe0000fff: Instrumentation Trace Macrocell */ +# define LM3S_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */ +# define LM3S_FPB_BASE 0xe0002000 /* -0xe0002fff: Flash Patch and Breakpoint */ + /* -0xe000dfff: Reserved */ +# define LM3S_NVIC_BASE 0xe000e000 /* -0xe000efff: Nested Vectored Interrupt Controller */ + /* -0xe003ffff: Reserved */ +# define LM3S_TPIU_BASE 0xe0040000 /* -0xe0040fff: Trace Port Interface Unit */ + /* -0xffffffff: Reserved */ +#else +# error "Memory map not specified for this LM3S chip" +#endif + +/* Peripheral base addresses ********************************************************/ +/* The LM3S6918 and LM3S6965 differ by only the presence or absence of a few differnt + * peripheral modules. They could probably be combined into one peripheral memory + * map. However, keeping them separate does also provide so early, compile-time + * error detection that makes the duplication worthwhile. + */ + +#if defined(CONFIG_ARCH_CHIP_LM3S6918) +/* FiRM Peripheral Base Addresses */ + +# 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 + 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 */ +#elif defined(CONFIG_ARCH_CHIP_LM3S6432) +/* FiRM Peripheral Base Addresses */ + +# 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 */ + /* -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 + 0x20000) /* -0x207ff: I2C Master 0 */ +# define LM3S_I2CS0_BASE (LM3S_PERIPH_BASE + 0x20800) /* -0x20fff: I2C Slave 0 */ + /* -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 */ + /* -0x27fff: Reserved */ +# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ + /* -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 */ + /* -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 */ + +#elif defined(CONFIG_ARCH_CHIP_LM3S6965) +/* FiRM Peripheral Base Addresses */ + +# 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 */ + /* -0x0bfff: Reserved */ +# define LM3S_UART0_BASE (LM3S_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ +# define LM3S_UART1_BASE (LM3S_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ +# define LM3S_UART2_BASE (LM3S_PERIPH_BASE + 0x0e000) /* -0x0dfff: UART2 */ + /* -0x1ffff: Reserved */ +/* Peripheral Base Addresses */ + +# 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 */ + /* -0x27fff: Reserved */ +# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ + /* -0x2bfff: Reserved */ +# define LM3S_QEI0_BASE (LM3S_PERIPH_BASE + 0x2c000) /* -0x2cfff: QEI0 */ +# define LM3S_QEI1_BASE (LM3S_PERIPH_BASE + 0x2d000) /* -0x2dfff: QEI1 */ + /* -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 */ +#elif defined(CONFIG_ARCH_CHIP_LM3S8962) +/* FiRM Peripheral Base Addresses */ + +# 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 */ + /* -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 + 0x20000) /* -0x207ff: I2C Master 0 */ +# define LM3S_I2CS0_BASE (LM3S_PERIPH_BASE + 0x20800) /* -0x20fff: I2C Slave 0 */ + /* -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 */ + /* -0x27fff: Reserved */ +# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ + /* -0x2bfff: Reserved */ +# define LM3S_QEI0_BASE (LM3S_PERIPH_BASE + 0x2c000) /* -0x2cfff: QEI0 */ +# define LM3S_QEI1_BASE (LM3S_PERIPH_BASE + 0x2d000) /* -0x2dfff: QEI1 */ + /* -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 */ + /* -0x3fffff: Reserved */ +# define LM3S_CANCON_BASE (LM3S_PERIPH_BASE + 0x40000) /* -0x40fff: CAN Controller */ + /* -0x47fff: Reserved */ +# define LM3S_ETHCON_BASE (LM3S_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ + /* -0xfcfff: Reserved */ +# define LM3S_HIBERNATE_BASE (LM3S_PERIPH_BASE + 0xfc000) /* -0xfcfff: Hibernation 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 */ +#elif defined(CONFIG_ARCH_CHIP_LM3S9B96) +/* FiRM Peripheral Base Addresses */ + +# 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: SSI0 */ + /* -0x0bfff: Reserved */ +# define LM3S_UART0_BASE (LM3S_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ +# define LM3S_UART1_BASE (LM3S_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ +# define LM3S_UART2_BASE (LM3S_PERIPH_BASE + 0x0e000) /* -0x0dfff: UART2 */ + /* -0x1ffff: Reserved */ +/* Peripheral Base Addresses */ + +# 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 */ + +# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ + /* -0x2bfff: Reserved */ +# define LM3S_QEI0_BASE (LM3S_PERIPH_BASE + 0x2c000) /* -0x2cfff: QEI0 */ +# define LM3S_QEI1_BASE (LM3S_PERIPH_BASE + 0x2d000) /* -0x2dfff: QEI1 */ + /* -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_ADC0_BASE (LM3S_PERIPH_BASE + 0x38000) /* -0x38fff: ADC 0 */ +# define LM3S_ADC1_BASE (LM3S_PERIPH_BASE + 0x39000) /* -0x39fff: ADC 1 */ + /* -0x3bfff: Reserved */ +# define LM3S_COMPARE_BASE (LM3S_PERIPH_BASE + 0x3c000) /* -0x3cfff: Analog Comparators */ +# define LM3S_GPIOJ_BASE (LM3S_PERIPH_BASE + 0x3d000) /* -0x3dfff: GPIO Port J */ + /* -0x3ffff: Reserved */ +# define LM3S_CAN0_BASE (LM3S_PERIPH_BASE + 0x40000) /* -0x40fff: CAN 0 */ +# define LM3S_CAN1_BASE (LM3S_PERIPH_BASE + 0x41000) /* -0x41fff: CAN 1 */ + /* -0x47fff: Reserved */ +# define LM3S_ETHCON_BASE (LM3S_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ + /* -0x49fff: Reserved */ +# define LM3S_USB_BASE (LM3S_PERIPH_BASE + 0x50000) /* -0x50fff: USB */ + /* -0x53fff: Reserved */ +# define LM3S_I2S0_BASE (LM3S_PERIPH_BASE + 0x54000) /* -0x54fff: I2S 0 */ + /* -0x57fff: Reserved */ +# define LM3S_GPIOAAHB_BASE (LM3S_PERIPH_BASE + 0x58000) /* -0x58fff: GPIO Port A (AHB aperture) */ +# define LM3S_GPIOBAHB_BASE (LM3S_PERIPH_BASE + 0x59000) /* -0x59fff: GPIO Port B (AHB aperture) */ +# define LM3S_GPIOCAHB_BASE (LM3S_PERIPH_BASE + 0x5A000) /* -0x5afff: GPIO Port C (AHB aperture) */ +# define LM3S_GPIODAHB_BASE (LM3S_PERIPH_BASE + 0x5B000) /* -0x5bfff: GPIO Port D (AHB aperture) */ +# define LM3S_GPIOEAHB_BASE (LM3S_PERIPH_BASE + 0x5C000) /* -0x5cfff: GPIO Port E (AHB aperture) */ +# define LM3S_GPIOFAHB_BASE (LM3S_PERIPH_BASE + 0x5D000) /* -0x5dfff: GPIO Port F (AHB aperture) */ +# define LM3S_GPIOGAHB_BASE (LM3S_PERIPH_BASE + 0x5E000) /* -0x5efff: GPIO Port G (AHB aperture) */ +# define LM3S_GPIOHAHB_BASE (LM3S_PERIPH_BASE + 0x5F000) /* -0x5ffff: GPIO Port H (AHB aperture) */ +# define LM3S_GPIOJAHB_BASE (LM3S_PERIPH_BASE + 0x60000) /* -0x60fff: GPIO Port J (AHB aperture) */ + /* -0xcffff: Reserved */ +# define LM3S_EPI0_BASE (LM3S_PERIPH_BASE + 0xD0000) /* -0xd0fff: EPI 0 */ + /* -0xfcfff: Reserved */ +# define LM3S_FLASHCON_BASE (LM3S_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ +# define LM3S_SYSCON_BASE (LM3S_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ +# define LM3S_UDMA_BASE (LM3S_PERIPH_BASE + 0xff000) /* -0xfffff: System Control */ + /* -0x1ffffff: Reserved */ +#else +# error "Peripheral base addresses not specified for this LM3S chip" +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h new file mode 100644 index 000000000..b56ca77cb --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h @@ -0,0 +1,235 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_ssi.h + * + * Copyright (C) 2009, 2013 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_CHIP_LM3S_SSI_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SSI_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#if LM3S_NSSI > 0 + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* SSI register offsets *************************************************************/ + +#define LM3S_SSI_CR0_OFFSET 0x000 /* SSI Control 0 */ +#define LM3S_SSI_CR1_OFFSET 0x004 /* SSI Control 1 */ +#define LM3S_SSI_DR_OFFSET 0x008 /* SSI Data */ +#define LM3S_SSI_SR_OFFSET 0x00c /* SSI Status */ +#define LM3S_SSI_CPSR_OFFSET 0x010 /* SSI Clock Prescale */ +#define LM3S_SSI_IM_OFFSET 0x014 /* SSI Interrupt Mask */ +#define LM3S_SSI_RIS_OFFSET 0x018 /* SSI Raw Interrupt Status */ +#define LM3S_SSI_MIS_OFFSET 0x01c /* SSI Masked Interrupt Status */ +#define LM3S_SSI_ICR_OFFSET 0x020 /* SSI Interrupt Clear */ +#define LM3S_SSI_PERIPHID4_OFFSET 0xfd0 /* SSI Peripheral Identification 4 */ +#define LM3S_SSI_PERIPHID5_OFFSET 0xfd4 /* SSI Peripheral Identification 5 */ +#define LM3S_SSI_PERIPHID6_OFFSET 0xfd8 /* SSI Peripheral Identification 6 */ +#define LM3S_SSI_PERIPHID7_OFFSET 0xfdc /* SSI Peripheral Identification 7 */ +#define LM3S_SSI_PERIPHID0_OFFSET 0xfe0 /* SSI Peripheral Identification 0 */ +#define LM3S_SSI_PERIPHID1_OFFSET 0xfe4 /* SSI Peripheral Identification 1 */ +#define LM3S_SSI_PERIPHID2_OFFSET 0xfe8 /* SSI Peripheral Identification 2 */ +#define LM3S_SSI_PERIPHID3_OFFSET 0xfec /* SSI Peripheral Identification 3 */ +#define LM3S_SSI_PCELLID0_OFFSET 0xff0 /* SSI PrimeCell Identification 0 */ +#define LM3S_SSI_PCELLID1_OFFSET 0xff4 /* SSI PrimeCell Identification 1 */ +#define LM3S_SSI_PCELLID2_OFFSET 0xff8 /* SSI PrimeCell Identification 2 */ +#define LM3S_SSI_PCELLID3_OFFSET 0xffc /* SSI PrimeCell Identification 3 */ + +/* SSI register addresses ***********************************************************/ + +#define LM3S_SSI0_CR0 (LM3S_SSI0_BASE + LM3S_SSI_CR0_OFFSET) +#define LM3S_SSI0_CR1 (LM3S_SSI0_BASE + LM3S_SSI_CR1_OFFSET) +#define LM3S_SSI0_DR (LM3S_SSI0_BASE + LM3S_SSI_DR_OFFSET) +#define LM3S_SSI0_SR (LM3S_SSI0_BASE + LM3S_SSI_SR_OFFSET) +#define LM3S_SSI0_CPSR (LM3S_SSI0_BASE + LM3S_SSI_CPSR_OFFSET) +#define LM3S_SSI0_IM (LM3S_SSI0_BASE + LM3S_SSI_IM_OFFSET) +#define LM3S_SSI0_RIS (LM3S_SSI0_BASE + LM3S_SSI_RIS_OFFSET) +#define LM3S_SSI0_MIS (LM3S_SSI0_BASE + LM3S_SSI_MIS_OFFSET) +#define LM3S_SSI0_ICR (LM3S_SSI0_BASE + LM3S_SSI_ICR_OFFSET) +#define LM3S_SSI0_PERIPHID4 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID4_OFFSET) +#define LM3S_SSI0_PERIPHID5 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID5_OFFSET) +#define LM3S_SSI0_PERIPHID6 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID6_OFFSET) +#define LM3S_SSI0_PERIPHID7 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID7_OFFSET) +#define LM3S_SSI0_PERIPHID0 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID0_OFFSET) +#define LM3S_SSI0_PERIPHID1 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID1_OFFSET) +#define LM3S_SSI0_PERIPHID2 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID2_OFFSET) +#define LM3S_SSI0_PERIPHID3 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID3_OFFSET) +#define LM3S_SSI0_PCELLID0 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID0_OFFSET) +#define LM3S_SSI0_PCELLID1 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID1_OFFSET) +#define LM3S_SSI0_PCELLID2 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID2_OFFSET) +#define LM3S_SSI0_PCELLID3 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID3_OFFSET) + +#if LM3S_NSSI > 1 +#define LM3S_SSI1_CR0 (LM3S_SSI1_BASE + LM3S_SSI_CR0_OFFSET) +#define LM3S_SSI1_CR1 (LM3S_SSI1_BASE + LM3S_SSI_CR1_OFFSET) +#define LM3S_SSI1_DR (LM3S_SSI1_BASE + LM3S_SSI_DR_OFFSET) +#define LM3S_SSI1_SR (LM3S_SSI1_BASE + LM3S_SSI_SR_OFFSET) +#define LM3S_SSI1_CPSR (LM3S_SSI1_BASE + LM3S_SSI_CPSR_OFFSET) +#define LM3S_SSI1_IM (LM3S_SSI1_BASE + LM3S_SSI_IM_OFFSET) +#define LM3S_SSI1_RIS (LM3S_SSI1_BASE + LM3S_SSI_RIS_OFFSET) +#define LM3S_SSI1_MIS (LM3S_SSI1_BASE + LM3S_SSI_MIS_OFFSET) +#define LM3S_SSI1_ICR (LM3S_SSI1_BASE + LM3S_SSI_ICR_OFFSET) +#define LM3S_SSI1_PERIPHID4 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID4_OFFSET) +#define LM3S_SSI1_PERIPHID5 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID5_OFFSET) +#define LM3S_SSI1_PERIPHID6 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID6_OFFSET) +#define LM3S_SSI1_PERIPHID7 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID7_OFFSET) +#define LM3S_SSI1_PERIPHID0 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID0_OFFSET) +#define LM3S_SSI1_PERIPHID1 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID1_OFFSET) +#define LM3S_SSI1_PERIPHID2 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID2_OFFSET) +#define LM3S_SSI1_PERIPHID3 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID3_OFFSET) +#define LM3S_SSI1_PCELLID0 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID0_OFFSET) +#define LM3S_SSI1_PCELLID1 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID1_OFFSET) +#define LM3S_SSI1_PCELLID2 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID2_OFFSET) +#define LM3S_SSI1_PCELLID3 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID3_OFFSET) + +#define LM3S_SSI_BASE(n) (LM3S_SSI0_BASE + (n)*0x01000) + +#define LM3S_SSI_CR0(n) (LM3S_SSI_BASE(n) + LM3S_SSI_CR0_OFFSET) +#define LM3S_SSI_CR1(n) (LM3S_SSI_BASE(n) + LM3S_SSI_CR1_OFFSET) +#define LM3S_SSI_DR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_DR_OFFSET) +#define LM3S_SSI_SR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_SR_OFFSET) +#define LM3S_SSI_CPSR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_CPSR_OFFSET) +#define LM3S_SSI_IM(n) (LM3S_SSI_BASE(n) + LM3S_SSI_IM_OFFSET) +#define LM3S_SSI_RIS(n) (LM3S_SSI_BASE(n) + LM3S_SSI_RIS_OFFSET) +#define LM3S_SSI_MIS(n) (LM3S_SSI_BASE(n) + LM3S_SSI_MIS_OFFSET) +#define LM3S_SSI_ICR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_ICR_OFFSET) +#define LM3S_SSI_PERIPHID4(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID4_OFFSET) +#define LM3S_SSI_PERIPHID5(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID5_OFFSET) +#define LM3S_SSI_PERIPHID6(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID6_OFFSET) +#define LM3S_SSI_PERIPHID7(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID7_OFFSET) +#define LM3S_SSI_PERIPHID0(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID0_OFFSET) +#define LM3S_SSI_PERIPHID1(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID1_OFFSET) +#define LM3S_SSI_PERIPHID2(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID2_OFFSET) +#define LM3S_SSI_PERIPHID3(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID3_OFFSET) +#define LM3S_SSI_PCELLID0(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID0_OFFSET) +#define LM3S_SSI_PCELLID1(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID1_OFFSET) +#define LM3S_SSI_PCELLID2(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID2_OFFSET) +#define LM3S_SSI_PCELLID3(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID3_OFFSET) +#endif /* LM3S_NSSI > 1 */ + +/* SSI register bit defitiions ******************************************************/ + +/* SSI Control 0 (SSICR0), offset 0x000 */ + +#define SSI_CR0_DSS_SHIFT 0 /* Bits 3-0: SSI Data Size Select */ +#define SSI_CR0_DSS_MASK (0x0f << SSI_CR0_DSS_SHIFT) +#define SSI_CR0_DSS(n) ((n-1) << SSI_CR0_DSS_SHIFT) /* n={4,5,..16} */ +#define SSI_CR0_FRF_SHIFT 4 /* Bits 5-4: SSI Frame Format Select */ +#define SSI_CR0_FRF_MASK (3 << SSI_CR0_FRF_SHIFT) +#define SSI_CR0_FRF_SPI (0 << SSI_CR0_FRF_SHIFT) /* Freescale SPI format */ +#define SSI_CR0_FRF_SSFF (1 << SSI_CR0_FRF_SHIFT) /* TI synchronous serial fram format */ +#define SSI_CR0_FRF_UWIRE (2 << SSI_CR0_FRF_SHIFT) /* MICROWIRE frame format */ +#define SSI_CR0_SPO (1 << 6) /* Bit 6: SSI Serial Clock Polarity */ +#define SSI_CR0_SPH (1 << 7) /* Bit 7: SSI Serial Clock Phase */ +#define SSI_CR0_SCR_SHIFT 8 /* Bits 15-8: SSI Serial Clock Rate */ +#define SSI_CR0_SCR_MASK (0xff << SSI_CR0_SCR_SHIFT) + +/* SSI Control 1 (SSICR1), offset 0x004 */ + +#define SSI_CR1_LBM (1 << 0) /* Bit 0: SSI Loopback Mode */ +#define SSI_CR1_SSE (1 << 1) /* Bit 1: SSI Synchronous Serial Port Enable */ +#define SSI_CR1_MS (1 << 2) /* Bit 2: SSI Master/Slave Select slave */ +#define SSI_CR1_SOD (1 << 3) /* Bit 3: SSI Slave Mode Output Disable */ + +/* SSI Data (SSIDR), offset 0x008 */ + +#define SSI_DR_MASK 0xffff /* Bits 15-0: SSI data */ + +/* SSI Status (SSISR), offset 0x00c */ + +#define SSI_SR_TFE (1 << 0) /* Bit 0: SSI Transmit FIFO Empty */ +#define SSI_SR_TNF (1 << 1) /* Bit 1: SSI Transmit FIFO Not Full */ +#define SSI_SR_RNE (1 << 2) /* Bit 2: SSI Receive FIFO Not Empty */ +#define SSI_SR_RFF (1 << 3) /* Bit 3: SSI Receive FIFO Full */ +#define SSI_SR_BSY (1 << 4) /* Bit 4: SSI Busy Bit */ + +/* SSI Clock Prescale (SSICPSR), offset 0x010 */ + +#define SSI_CPSR_DIV_MASK 0xff /* Bits 7-0: SSI Clock Prescale Divisor */ + +/* SSI Interrupt Mask (SSIIM), offset 0x014 */ + +#define SSI_IM_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Interrupt Mask */ +#define SSI_IM_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Interrupt Mask */ +#define SSI_IM_RX (1 << 2) /* Bit 2: SSI Receive FIFO Interrupt Mask */ +#define SSI_IM_TX (1 << 3) /* Bit 3: SSI Transmit FIFO Interrupt Mask */ + +/* SSI Raw Interrupt Status (SSIRIS), offset 0x018 */ + +#define SSI_RIS_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Raw Interrupt Status */ +#define SSI_RIS_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Raw Interrupt Status */ +#define SSI_RIS_RX (1 << 2) /* Bit 2: SSI Receive FIFO Raw Interrupt Status */ +#define SSI_RIS_TX (1 << 3) /* Bit 3: SSI Transmit FIFO Raw Interrupt Status */ + +/* SSI Masked Interrupt Status (SSIMIS), offset 0x01c */ + +#define SSI_MIS_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Masked Interrupt Status */ +#define SSI_MIS_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Masked Interrupt Status */ +#define SSI_MIS_RX (1 << 2) /* Bit 2: SSI Receive FIFO Masked Interrupt Status */ +#define SSI_MIS_TX (1 << 3) /* Bit 3: SSI Transmit FIFO Masked Interrupt Status */ + +/* SSI Interrupt Clear (SSIICR), offset 0x020 */ + +#define SSI_ICR_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Interrupt Clear */ +#define SSI_ICR_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Interrupt Clear */ + +/* SSI Peripheral Identification n (SSIPERIPHIDn), offset 0xfd0-0xfec */ + +#define SSI_PERIPHID_MASK 0xff /* Bits 7-0: SSI Peripheral ID n */ + +/* SSI PrimeCell Identification n (SSIPCELLIDn), offset 0xff0-0xffc */ + +#define SSI_PCELLID_MASK 0xff /* Bits 7-0: SSI Prime cell ID */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* LM3S_NSSI > 0 */ +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SSI_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h new file mode 100644 index 000000000..d66cfeb47 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h @@ -0,0 +1,495 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_syscontrol.h + * + * Copyright (C) 2009-2010, 2013 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_CHIP_LM3S_SYSCONTROL_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SYSCONTROL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* System Control Register Offsets **************************************************/ + +#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*/ + +/* 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_MINOR_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_GPIO(n) (1 << (n)) +#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) +# define SYSCON_LPDOPCTL_2500MV (0x00 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.5V (reset)*/ +# define SYSCON_LPDOPCTL_2450MV (0x01 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.45V */ +# define SYSCON_LPDOPCTL_2400MV (0x02 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.4V */ +# define SYSCON_LPDOPCTL_2350MV (0x03 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.35V */ +# define SYSCON_LPDOPCTL_2300MV (0x04 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.3V */ +# define SYSCON_LPDOPCTL_2250MV (0x05 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.25V */ +# define SYSCON_LPDOPCTL_2750MV (0x1b << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.75V */ +# define SYSCON_LPDOPCTL_2700MV (0x1c << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.7V */ +# define SYSCON_LPDOPCTL_2650MV (0x1d << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.65V */ +# define SYSCON_LPDOPCTL_2600MV (0x1e << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.6V */ +# define SYSCON_LPDOPCTL_2550MV (0x1f << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.55V */ + +/* 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_GPIO(n) (1 << (n)) +#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_OSCSRC_MOSC (0 << SYSCON_RCC_OSCSRC_SHIFT) /* Main oscillator */ +# define SYSCON_RCC_OSCSRC_IOSC (1 << SYSCON_RCC_OSCSRC_SHIFT) /* Internal oscillator (reset) */ +# define SYSCON_RCC_OSCSRC_IOSC4 (2 << SYSCON_RCC_OSCSRC_SHIFT) /* Internal oscillator / 4 */ +# define SYSCON_RCC_OSCSRC_30KHZ (3 << SYSCON_RCC_OSCSRC_SHIFT) /* 30KHz internal oscillator */ +#define SYSCON_RCC_XTAL_SHIFT 6 /* Bits 10-6: Crystal Value */ +#define SYSCON_RCC_XTAL_MASK (0x1f << SYSCON_RCC_XTAL_SHIFT) +# define SYSCON_RCC_XTAL1000KHZ ( 0 << SYSCON_RCC_XTAL_SHIFT) /* 1.0000MHz (NO PLL) */ +# define SYSCON_RCC_XTAL1843KHZ ( 1 << SYSCON_RCC_XTAL_SHIFT) /* 1.8432MHz (NO PLL) */ +# define SYSCON_RCC_XTAL2000KHZ ( 2 << SYSCON_RCC_XTAL_SHIFT) /* 2.0000MHz (NO PLL) */ +# define SYSCON_RCC_XTAL2580KHZ ( 3 << SYSCON_RCC_XTAL_SHIFT) /* 2.4576MHz (NO PLL) */ +# define SYSCON_RCC_XTAL3580KHZ ( 4 << SYSCON_RCC_XTAL_SHIFT) /* 3.5795MHz */ +# define SYSCON_RCC_XTAL3686KHZ ( 5 << SYSCON_RCC_XTAL_SHIFT) /* 3.6864MHz */ +# define SYSCON_RCC_XTAL4000KHZ ( 6 << SYSCON_RCC_XTAL_SHIFT) /* 4.0000MHz */ +# define SYSCON_RCC_XTAL4096KHZ ( 7 << SYSCON_RCC_XTAL_SHIFT) /* 4.0960MHz */ +# define SYSCON_RCC_XTAL4915KHZ ( 8 << SYSCON_RCC_XTAL_SHIFT) /* 4.9152MHz */ +# define SYSCON_RCC_XTAL5000KHZ ( 9 << SYSCON_RCC_XTAL_SHIFT) /* 5.0000MHz */ +# define SYSCON_RCC_XTAL5120KHZ (10 << SYSCON_RCC_XTAL_SHIFT) /* 5.1200MHz */ +# define SYSCON_RCC_XTAL6000KHZ (11 << SYSCON_RCC_XTAL_SHIFT) /* 6.0000MHz (reset value) */ +# define SYSCON_RCC_XTAL6144KHZ (12 << SYSCON_RCC_XTAL_SHIFT) /* 6.1440MHz */ +# define SYSCON_RCC_XTAL7373KHZ (13 << SYSCON_RCC_XTAL_SHIFT) /* 7.3728MHz */ +# define SYSCON_RCC_XTAL8000KHZ (14 << SYSCON_RCC_XTAL_SHIFT) /* 8.0000MHz */ +# define SYSCON_RCC_XTAL8192KHZ (15 << SYSCON_RCC_XTAL_SHIFT) /* 8.1920MHz */ +#ifdef CONFIG_ARCH_CHIP_LM3S9B96 +# define SYSCON_RCC_XTAL10000KHZ (16 << SYSCON_RCC_XTAL_SHIFT) /* 10.0 MHz (USB) */ +# define SYSCON_RCC_XTAL12000KHZ (17 << SYSCON_RCC_XTAL_SHIFT) /* 12.0 MHz (USB) */ +# define SYSCON_RCC_XTAL12888KHZ (18 << SYSCON_RCC_XTAL_SHIFT) /* 12.288 MHz */ +# define SYSCON_RCC_XTAL13560KHZ (19 << SYSCON_RCC_XTAL_SHIFT) /* 13.56 MHz */ +# define SYSCON_RCC_XTAL14318KHZ (20 << SYSCON_RCC_XTAL_SHIFT) /* 14.31818 MHz */ +# define SYSCON_RCC_XTAL16000KHZ (21 << SYSCON_RCC_XTAL_SHIFT) /* 16.0 MHz (USB) */ +# define SYSCON_RCC_XTAL16384KHZ (22 << SYSCON_RCC_XTAL_SHIFT) /* 16.384 MHz */ +#endif +#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 23 /* Bits 26-23: System Clock Divisor */ +#define SYSCON_RCC_SYSDIV_MASK (0x0f << SYSCON_RCC_SYSDIV_SHIFT) +# define SYSCON_RCC_SYSDIV(n) (((n)-1) << 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_OSCSRC2_MOSC (0 << SYSCON_RCC2_OSCSRC2_SHIFT) /* Main oscillator */ +# define SYSCON_RCC2_OSCSRC2_IOSC (1 << SYSCON_RCC2_OSCSRC2_SHIFT) /* Internal oscillator (reset) */ +# define SYSCON_RCC2_OSCSRC2_IOSC4 (2 << SYSCON_RCC2_OSCSRC2_SHIFT) /* Internal oscillator / 4 */ +# define SYSCON_RCC2_OSCSRC2_30KHZ (3 << SYSCON_RCC2_OSCSRC2_SHIFT) /* 30KHz internal oscillator */ +# define SYSCON_RCC2_OSCSRC2_32KHZ (7 << SYSCON_RCC2_OSCSRC2_SHIFT) /* 32.768KHz external oscillator */ +#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_SYSDIV(n) ((n-1) << 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_GPIO(n) (1 << (n)) +#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_GPIO(n) (1 << (n)) +#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_GPIO(n) (1 << (n)) +#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_CHIP_LM3S_SYSCONTROL_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h new file mode 100644 index 000000000..649737f13 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h @@ -0,0 +1,125 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_timer.h + * + * Copyright (C) 2012 Max Nekludov. All rights reserved. + * Author: Max Nekludov + * + * 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_CHIP_LM3S_TIMER_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_TIMER_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Timer register offsets ***********************************************************/ + +#define TIMER_GPTMCFG_OFFSET 0x000 +#define TIMER_GPTMTAMR_OFFSET 0x004 +#define TIMER_GPTMCTL_OFFSET 0x00C +#define TIMER_GPTMIMR_OFFSET 0x018 +#define TIMER_GPTMRIS_OFFSET 0x01C +#define TIMER_GPTMICR_OFFSET 0x024 +#define TIMER_GPTMTAILR_OFFSET 0x028 +#define TIMER_GPTMTAR_OFFSET 0x048 + +/* SSI register addresses ***********************************************************/ + +#define LM3S_TIMER_BASE(n) (LM3S_TIMER0_BASE + (n)*0x01000) + +#define LM3S_TIMER_GPTMCFG(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMCFG_OFFSET) +#define LM3S_TIMER_GPTMTAMR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMTAMR_OFFSET) +#define LM3S_TIMER_GPTMCTL(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMCTL_OFFSET) +#define LM3S_TIMER_GPTMIMR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMIMR_OFFSET) +#define LM3S_TIMER_GPTMRIS(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMRIS_OFFSET) +#define LM3S_TIMER_GPTMICR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMICR_OFFSET) +#define LM3S_TIMER_GPTMTAILR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMTAILR_OFFSET) +#define LM3S_TIMER_GPTMTAR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMTAR_OFFSET) + +/* SSI register bit defitiions ******************************************************/ + +/* GPTM Configuration (GPTMCFG), offset 0x000 */ + +#define TIMER_GPTMCFG_CFG_SHIFT 0 /* Bits 2-0: GPTM Configuration */ +#define TIMER_GPTM_CFG_MASK (0x07 << TIMER_GPTMCFG_CFG_SHIFT) +#define TIMER_GPTMCFG_CFG_32 (0 << TIMER_GPTMCFG_CFG_SHIFT) /* 32-bit timer configuration */ +#define TIMER_GPTMCFG_CFG_RTC (1 << TIMER_GPTMCFG_CFG_SHIFT) /* 32-bit real-time clock (RTC) counter configuration */ +#define TIMER_GPTMCFG_CFG_16 (1 << TIMER_GPTMCFG_CFG_SHIFT) /* 16-bit timer configuration */ + +/* GPTM Timer A Mode (GPTMTAMR), offset 0x004 */ + +#define TIMER_GPTMTAMR_TAMR_SHIFT 0 /* Bits 1-0: GPTM Timer A Mode */ +#define TIMER_GPTMTAMR_TAMR_MASK (0x03 << TIMER_GPTMTAMR_TAMR_SHIFT) +#define TIMER_GPTMTAMR_TAMR_ONESHOT (1 << TIMER_GPTMTAMR_TAMR_SHIFT) /* One-Shot Timer mode */ +#define TIMER_GPTMTAMR_TAMR_PERIODIC (2 << TIMER_GPTMTAMR_TAMR_SHIFT) /* Periodic Timer mode */ +#define TIMER_GPTMTAMR_TAMR_CAPTURE (3 << TIMER_GPTMTAMR_TAMR_SHIFT) /* Capture mode */ +#define TIMER_GPTMTAMR_TACMR_SHIFT 2 /* Bits 2: GPTM Timer A Capture Mode */ +#define TIMER_GPTMTAMR_TACMR_MASK (0x01 << TIMER_GPTMTAMR_TACMR_SHIFT) +#define TIMER_GPTMTAMR_TACMR_EDGECOUNT (0 << TIMER_GPTMTAMR_TACMR_SHIFT) /* Edge-Count mode */ +#define TIMER_GPTMTAMR_TACMR_EDGETIME (1 << TIMER_GPTMTAMR_TACMR_SHIFT) /* Edge-Time mode */ +#define TIMER_GPTMTAMR_TAAMS_SHIFT 3 /* Bits 3: GPTM Timer A Alternate Mode Select */ +#define TIMER_GPTMTAMR_TAAMS_MASK (0x01 << TIMER_GPTMTAMR_TAAMS_SHIFT) +#define TIMER_GPTMTAMR_TAAMS_CAPTURE (0 << TIMER_GPTMTAMR_TAAMS_SHIFT) /* Capture mode is enabled */ +#define TIMER_GPTMTAMR_TAAMS_PWM (1 << TIMER_GPTMTAMR_TAAMS_SHIFT) /* PWM mode is enabled */ +#define TIMER_GPTMTAMR_TACDIR_SHIFT 4 /* Bits 4: GPTM Timer A Count Direction */ +#define TIMER_GPTMTAMR_TACDIR_MASK (0x01 << TIMER_GPTMTAMR_TACDIR_SHIFT) +#define TIMER_GPTMTAMR_TACDIR_DOWN (0 << TIMER_GPTMTAMR_TACDIR_SHIFT) /* The timer counts down */ +#define TIMER_GPTMTAMR_TACDIR_UP (1 << TIMER_GPTMTAMR_TACDIR_SHIFT) /* When in one-shot or periodic mode, the timer counts up */ +#define TIMER_GPTMTAMR_TAMIE_SHIFT 5 /* Bits 5: GPTM Timer A Match Interrupt Enable */ +#define TIMER_GPTMTAMR_TAMIE_MASK (0x01 << TIMER_GPTMTAMR_TAMIE_SHIFT) + +/* GPTM Control (GPTMCTL), offset 0x00C */ + +#define TIMER_GPTMCTL_TAEN_SHIFT 0 /* Bits 0: GPTM Timer A Enable */ +#define TIMER_GPTMCTL_TAEN_MASK (0x01 << TIMER_GPTMCTL_TAEN_SHIFT) +#define TIMER_GPTMCTL_TASTALL_SHIFT 1 /* Bits 1: GPTM Timer A Stall Enable */ +#define TIMER_GPTMCTL_TASTALL_MASK (0x01 << TIMER_GPTMCTL_TASTALL_SHIFT) + +/* GPTM Interrupt Mask (GPTMIMR), offset 0x018 */ + +#define TIMER_GPTMIMR_TATOIM_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Interrupt Mask */ +#define TIMER_GPTMIMR_TATOIM_MASK (0x01 << TIMER_GPTMIMR_TATOIM_SHIFT) + +/* GPTM Raw Interrupt Status (GPTMRIS), offset 0x01C */ + +#define TIMER_GPTMRIS_TATORIS_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Raw Interrupt */ +#define TIMER_GPTMRIS_TATORIS_MASK (0x01 << TIMER_GPTMRIS_TATORIS_SHIFT) + +/* GPTM Interrupt Clear (GPTMICR), offset 0x024 */ + +#define TIMER_GPTMICR_TATOCINT_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Raw Interrupt Clear*/ +#define TIMER_GPTMICR_TATOCINT_MASK (0x01 << TIMER_GPTMICR_TATOCINT_SHIFT) + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_TIMER_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h new file mode 100644 index 000000000..0fef5ccf7 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h @@ -0,0 +1,347 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm3s_uart.h + * + * Copyright (C) 2009, 2013 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_CHIP_LM3S_UART_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_UART_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* UART register offsets ************************************************************/ + +#define LM3S_UART_DR_OFFSET 0x000 /* UART Data */ +#define LM3S_UART_RSR_OFFSET 0x004 /* UART Receive Status */ +#define LM3S_UART_ECR_OFFSET 0x004 /* UART Error Clear */ +#define LM3S_UART_FR_OFFSET 0x018 /* UART Flag */ +#define LM3S_UART_ILPR_OFFSET 0x020 /* UART IrDA Low-Power Register */ +#define LM3S_UART_IBRD_OFFSET 0x024 /* UART Integer Baud-Rate Divisor*/ +#define LM3S_UART_FBRD_OFFSET 0x028 /* UART Fractional Baud-Rate Divisor */ +#define LM3S_UART_LCRH_OFFSET 0x02c /* UART Line Control */ +#define LM3S_UART_CTL_OFFSET 0x030 /* UART Control */ +#define LM3S_UART_IFLS_OFFSET 0x034 /* UART Interrupt FIFO Level Select */ +#define LM3S_UART_IM_OFFSET 0x038 /* UART Interrupt Mask */ +#define LM3S_UART_RIS_OFFSET 0x03c /* UART Raw Interrupt Status */ +#define LM3S_UART_MIS_OFFSET 0x040 /* UART Masked Interrupt Status */ +#define LM3S_UART_ICR_OFFSET 0x044 /* UART Interrupt Clear */ +#define LM3S_UART_PERIPHID4_OFFSET 0xfd0 /* UART Peripheral Identification 4 */ +#define LM3S_UART_PERIPHID5_OFFSET 0xfd4 /* UART Peripheral Identification 5 */ +#define LM3S_UART_PERIPHID6_OFFSET 0xfd8 /* UART Peripheral Identification 6 */ +#define LM3S_UART_PERIPHID7_OFFSET 0xfdc /* UART Peripheral Identification 7 */ +#define LM3S_UART_PERIPHID0_OFFSET 0xfe0 /* UART Peripheral Identification 0 */ +#define LM3S_UART_PERIPHID1_OFFSET 0xfe4 /* UART Peripheral Identification 1 */ +#define LM3S_UART_PERIPHID2_OFFSET 0xfe8 /* UART Peripheral Identification 2 */ +#define LM3S_UART_PERIPHID3_OFFSET 0xfec /* UART Peripheral Identification 3 */ +#define LM3S_UART_PCELLID0_OFFSET 0xff0 /* UART PrimeCell Identification 0 */ +#define LM3S_UART_PCELLID1_OFFSET 0xff4 /* UART PrimeCell Identification 1 */ +#define LM3S_UART_PCELLID2_OFFSET 0xff8 /* UART PrimeCell Identification 2 */ +#define LM3S_UART_PCELLID3_OFFSET 0xffc /* UART PrimeCell Identification 3 */ + +/* UART register addresses **********************************************************/ + +#define LM3S_UART_BASE(n) (LM3S_UART0_BASE + (n)*0x01000) + +#define LM3S_UART_DR(n) (LM3S_UART_BASE(n) + LM3S_UART_DR_OFFSET) +#define LM3S_UART_RSR(n) (LM3S_UART_BASE(n) + LM3S_UART_RSR_OFFSET) +#define LM3S_UART_ECR(n) (LM3S_UART_BASE(n) + LM3S_UART_ECR_OFFSET) +#define LM3S_UART_FR(n) (LM3S_UART_BASE(n) + LM3S_UART_FR_OFFSET) +#define LM3S_UART_ILPR(n) (LM3S_UART_BASE(n) + LM3S_UART_ILPR_OFFSET) +#define LM3S_UART_IBRD(n) (LM3S_UART_BASE(n) + LM3S_UART_IBRD_OFFSET) +#define LM3S_UART_FBRD(n) (LM3S_UART_BASE(n) + LM3S_UART_FBRD_OFFSET) +#define LM3S_UART_LCRH(n) (LM3S_UART_BASE(n) + LM3S_UART_LCRH_OFFSET) +#define LM3S_UART_CTL(n) (LM3S_UART_BASE(n) + LM3S_UART_CTL_OFFSET) +#define LM3S_UART_IFLS(n) (LM3S_UART_BASE(n) + LM3S_UART_IFLS_OFFSET) +#define LM3S_UART_IM(n) (LM3S_UART_BASE(n) + LM3S_UART_IM_OFFSET) +#define LM3S_UART_RIS(n) (LM3S_UART_BASE(n) + LM3S_UART_RIS_OFFSET) +#define LM3S_UART_MIS(n) (LM3S_UART_BASE(n) + LM3S_UART_MIS_OFFSET) +#define LM3S_UART_ICR(n) (LM3S_UART_BASE(n) + LM3S_UART_ICR_OFFSET) +#define LM3S_UART_PERIPHID4(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID4_OFFSET) +#define LM3S_UART_PERIPHID5(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID5_OFFSET) +#define LM3S_UART_PERIPHID6(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID6_OFFSET) +#define LM3S_UART_PERIPHID7(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID7_OFFSET) +#define LM3S_UART_PERIPHID0(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID0_OFFSET) +#define LM3S_UART_PERIPHID1(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID1_OFFSET) +#define LM3S_UART_PERIPHID2(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID2_OFFSET) +#define LM3S_UART_PERIPHID3(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID3_OFFSET) +#define LM3S_UART_PCELLID0(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID0_OFFSET) +#define LM3S_UART_PCELLID1(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID1_OFFSET) +#define LM3S_UART_PCELLID2(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID2_OFFSET) +#define LM3S_UART_PCELLID3(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID3_OFFSET) + +#define LM3S_UART0_DR (LM3S_UART0_BASE + LM3S_UART_TDR_OFFSET) +#define LM3S_UART0_RSR (LM3S_UART0_BASE + LM3S_UART_RSR_OFFSET) +#define LM3S_UART0_ECR (LM3S_UART0_BASE + LM3S_UART_ECR_OFFSET) +#define LM3S_UART0_FR (LM3S_UART0_BASE + LM3S_UART_FR_OFFSET) +#define LM3S_UART0_ILPR (LM3S_UART0_BASE + LM3S_UART_ILPR_OFFSET) +#define LM3S_UART0_IBRD (LM3S_UART0_BASE + LM3S_UART_IBRD_OFFSET) +#define LM3S_UART0_FBRD (LM3S_UART0_BASE + LM3S_UART_FBRD_OFFSET) +#define LM3S_UART0_LCRH (LM3S_UART0_BASE + LM3S_UART_LCRH_OFFSET) +#define LM3S_UART0_CTL (LM3S_UART0_BASE + LM3S_UART_CTL_OFFSET) +#define LM3S_UART0_IFLS (LM3S_UART0_BASE + LM3S_UART_IFLS_OFFSET) +#define LM3S_UART0_IM (LM3S_UART0_BASE + LM3S_UART_IM_OFFSET) +#define LM3S_UART0_RIS (LM3S_UART0_BASE + LM3S_UART_RIS_OFFSET) +#define LM3S_UART0_MIS (LM3S_UART0_BASE + LM3S_UART_MIS_OFFSET) +#define LM3S_UART0_ICR (LM3S_UART0_BASE + LM3S_UART_ICR_OFFSET) +#define LM3S_UART0_PERIPHID4 (LM3S_UART0_BASE + LM3S_UART_PERIPHID4_OFFSET) +#define LM3S_UART0_PERIPHID5 (LM3S_UART0_BASE + LM3S_UART_PERIPHID5_OFFSET) +#define LM3S_UART0_PERIPHID6 (LM3S_UART0_BASE + LM3S_UART_PERIPHID6_OFFSET) +#define LM3S_UART0_PERIPHID7 (LM3S_UART0_BASE + LM3S_UART_PERIPHID7_OFFSET) +#define LM3S_UART0_PERIPHID0 (LM3S_UART0_BASE + LM3S_UART_PERIPHID0_OFFSET) +#define LM3S_UART0_PERIPHID1 (LM3S_UART0_BASE + LM3S_UART_PERIPHID1_OFFSET) +#define LM3S_UART0_PERIPHID2 (LM3S_UART0_BASE + LM3S_UART_PERIPHID2_OFFSET) +#define LM3S_UART0_PERIPHID3 (LM3S_UART0_BASE + LM3S_UART_PERIPHID3_OFFSET) +#define LM3S_UART0_PCELLID0 (LM3S_UART0_BASE + LM3S_UART_PCELLID0_OFFSET) +#define LM3S_UART0_PCELLID1 (LM3S_UART0_BASE + LM3S_UART_PCELLID1_OFFSET) +#define LM3S_UART0_PCELLID2 (LM3S_UART0_BASE + LM3S_UART_PCELLID2_OFFSET) +#define LM3S_UART0_PCELLID3 (LM3S_UART0_BASE + LM3S_UART_PCELLID3_OFFSET) + +#define LM3S_UART1_DR (LM3S_UART1_BASE + LM3S_UART_DR_OFFSET) +#define LM3S_UART1_RSR (LM3S_UART1_BASE + LM3S_UART_RSR_OFFSET) +#define LM3S_UART1_ECR (LM3S_UART1_BASE + LM3S_UART_ECR_OFFSET) +#define LM3S_UART1_FR (LM3S_UART1_BASE + LM3S_UART_FR_OFFSET) +#define LM3S_UART1_ILPR (LM3S_UART1_BASE + LM3S_UART_ILPR_OFFSET) +#define LM3S_UART1_IBRD (LM3S_UART1_BASE + LM3S_UART_IBRD_OFFSET) +#define LM3S_UART1_FBRD (LM3S_UART1_BASE + LM3S_UART_FBRD_OFFSET) +#define LM3S_UART1_LCRH (LM3S_UART1_BASE + LM3S_UART_LCRH_OFFSET) +#define LM3S_UART1_CTL (LM3S_UART1_BASE + LM3S_UART_CTL_OFFSET) +#define LM3S_UART1_IFLS (LM3S_UART1_BASE + LM3S_UART_IFLS_OFFSET) +#define LM3S_UART1_IM (LM3S_UART1_BASE + LM3S_UART_IM_OFFSET) +#define LM3S_UART1_RIS (LM3S_UART1_BASE + LM3S_UART_RIS_OFFSET) +#define LM3S_UART1_MIS (LM3S_UART1_BASE + LM3S_UART_MIS_OFFSET) +#define LM3S_UART1_ICR (LM3S_UART1_BASE + LM3S_UART_ICR_OFFSET) +#define LM3S_UART1_PERIPHID4 (LM3S_UART1_BASE + LM3S_UART_PERIPHID4_OFFSET) +#define LM3S_UART1_PERIPHID5 (LM3S_UART1_BASE + LM3S_UART_PERIPHID5_OFFSET) +#define LM3S_UART1_PERIPHID6 (LM3S_UART1_BASE + LM3S_UART_PERIPHID6_OFFSET) +#define LM3S_UART1_PERIPHID7 (LM3S_UART1_BASE + LM3S_UART_PERIPHID7_OFFSET) +#define LM3S_UART1_PERIPHID0 (LM3S_UART1_BASE + LM3S_UART_PERIPHID0_OFFSET) +#define LM3S_UART1_PERIPHID1 (LM3S_UART1_BASE + LM3S_UART_PERIPHID1_OFFSET) +#define LM3S_UART1_PERIPHID2 (LM3S_UART1_BASE + LM3S_UART_PERIPHID2_OFFSET) +#define LM3S_UART1_PERIPHID3 (LM3S_UART1_BASE + LM3S_UART_PERIPHID3_OFFSET) +#define LM3S_UART1_PCELLID0 (LM3S_UART1_BASE + LM3S_UART_PCELLID0_OFFSET) +#define LM3S_UART1_PCELLID1 (LM3S_UART1_BASE + LM3S_UART_PCELLID1_OFFSET) +#define LM3S_UART1_PCELLID2 (LM3S_UART1_BASE + LM3S_UART_PCELLID2_OFFSET) +#define LM3S_UART1_PCELLID3 (LM3S_UART1_BASE + LM3S_UART_PCELLID3_OFFSET) + +/* UART register bit settings *******************************************************/ + +/* UART Data (DR), offset 0x000 */ + +#define UART_DR_DATA_SHIFT 0 /* Bits 7-0: Data Transmitted or Received */ +#define UART_DR_DATA_MASK (0xff << UART_DR_DATA_SHIFT) +#define UART_DR_FE (1 << 8) /* Bit 8: UART Framing Error */ +#define UART_DR_PE (1 << 9) /* Bit 9: UART Parity Error */ +#define UART_DR_BE (1 << 10) /* Bit 10: UART Break Error */ +#define UART_DR_OE (1 << 11) /* Bit 11: UART Overrun Error */ + +/* UART Receive Status (RSR), offset 0x004 */ + +#define UART_RSR_FE (1 << 0) /* Bit 0: UART Framing Error */ +#define UART_RSR_PE (1 << 1) /* Bit 1: UART Parity Error */ +#define UART_RSR_BE (1 << 2) /* Bit 2: UART Break Error */ +#define UART_RSR_OE (1 << 3) /* Bit 3: UART Overrun Error */ + +/* UART Error Clear (ECR), offset 0x004 */ +/* Writing any value to this register clears pending error indications */ + +/* UART Flag (FR), offset 0x018 */ + +#define UART_FR_BUSY (1 << 3) /* Bit 3: UART Busy */ +#define UART_FR_RXFE (1 << 4) /* Bit 4: UART Receive FIFO Empty */ +#define UART_FR_TXFF (1 << 5) /* Bit 5: UART Transmit FIFO Full */ +#define UART_FR_RXFF (1 << 6) /* Bit 6: UART Receive FIFO Full */ +#define UART_FR_TXFE (1 << 7) /* Bit 7: UART Transmit FIFO Empty */ + +/* UART IrDA Low-Power Register (ILPR), offset 0x020 */ + +#define UART_ILPR_DVSR_MASK (0xff) /* Bits 7-0: IrDA Low-Power Divisor */ + +/* UART Integer Baud-Rate Divisor (IBRD), offset 0x024 */ + +#define UART_IBRD_DIVINT_MASK (0xffff) /* Bits 15-0: Integer Baud-Rate Divisor */ + +/* UART Fractional Baud-Rate Divisor (UARTFBRD), offset 0x028 */ + +#define UART_FBRD_DIVFRAC_MASK (0x3f) /* Bits 5-0: Fractional Baud-Rate Divisor */ + +/* Register 7: UART Line Control (LCRH), offset 0x02C */ + +#define UART_LCRH_BRK (1 << 0) /* Bit 0: UART Send Break */ +#define UART_LCRH_PEN (1 << 1) /* Bit 1: UART Parity Enable */ +#define UART_LCRH_EPS (1 << 2) /* Bit 2: UART Even Parity Select */ +#define UART_LCRH_STP2 (1 << 3) /* Bit 3: UART Two Stop Bits Select */ +#define UART_LCRH_FEN (1 << 4) /* Bit 4: UART Enable FIFOs */ +#define UART_LCRH_WLEN_SHIFT 5 /* Bits 6-5: UART Word Length */ +#define UART_LCRH_WLEN_MASK (3 << UART_LCRH_WLEN_SHIFT) +# define UART_LCRH_WLEN_5BITS (0 << UART_LCRH_WLEN_SHIFT) /* 5-bits (reset) */ +# define UART_LCRH_WLEN_6BITS (1 << UART_LCRH_WLEN_SHIFT) /* 6-bits */ +# define UART_LCRH_WLEN_7BITS (2 << UART_LCRH_WLEN_SHIFT) /* 7-bits */ +# define UART_LCRH_WLEN_8BITS (3 << UART_LCRH_WLEN_SHIFT) /* 8-bits */ +#define UART_LCRH_SPS (1 << 7) /* Bit 7: UART Stick Parity Select */ + +/* UART Control (CTL), offset 0x030 */ + +#define UART_CTL_UARTEN (1 << 0) /* Bit 0: UART Enable */ +#define UART_CTL_SIREN (1 << 1) /* Bit 1: UART SIR Enable */ +#define UART_CTL_SIRLP (1 << 2) /* Bit 2: UART SIR Low Power Mode */ +#define UART_CTL_LBE (1 << 7) /* Bit 7: UART Loop Back Enable */ +#define UART_CTL_TXE (1 << 8) /* Bit 8: UART Transmit Enable */ +#define UART_CTL_RXE (1 << 9) /* Bit 9: UART Receive Enable */ + +/* UART Interrupt FIFO Level Select (IFLS), offset 0x034 */ + +#define UART_IFLS_TXIFLSEL_SHIFT 0 /* Bits 2-0: UART Transmit Interrupt FIFO Level Select */ +#define UART_IFLS_TXIFLSEL_MASK (7 << UART_IFLS_TXIFLSEL_SHIFT) +# define UART_IFLS_TXIFLSEL_18th (0 << UART_IFLS_TXIFLSEL_SHIFT) /* 1/8th full */ +# define UART_IFLS_TXIFLSEL_14th (1 << UART_IFLS_TXIFLSEL_SHIFT) /* 1/4th full */ +# define UART_IFLS_TXIFLSEL_half (2 << UART_IFLS_TXIFLSEL_SHIFT) /* half full */ +# define UART_IFLS_TXIFLSEL_34th (3 << UART_IFLS_TXIFLSEL_SHIFT) /* 3/4th full */ +# define UART_IFLS_TXIFLSEL_78th (4 << UART_IFLS_TXIFLSEL_SHIFT) /* 7/8th full */ +#define UART_IFLS_RXIFLSEL_SHIFT 3 /* Bits 5-3: UART Receive Interrupt FIFO Level Select */ +#define UART_IFLS_RXIFLSEL_MASK (7 << UART_IFLS_RXIFLSEL_SHIFT) +# define UART_IFLS_RXIFLSEL_18th (0 << UART_IFLS_RXIFLSEL_SHIFT) /* 1/8th full */ +# define UART_IFLS_RXIFLSEL_14th (1 << UART_IFLS_RXIFLSEL_SHIFT) /* 1/4th full */ +# define UART_IFLS_RXIFLSEL_half (2 << UART_IFLS_RXIFLSEL_SHIFT) /* half full */ +# define UART_IFLS_RXIFLSEL_34th (3 << UART_IFLS_RXIFLSEL_SHIFT) /* 3/4th full */ +# define UART_IFLS_RXIFLSEL_78th (4 << UART_IFLS_RXIFLSEL_SHIFT) /* 7/8th full */ + +/* UART Interrupt Mask (IM), offset 0x038 */ + +#define UART_IM_RXIM (1 << 4) /* Bit 4: UART Receive Interrupt Mask */ +#define UART_IM_TXIM (1 << 5) /* Bit 5: UART Transmit Interrupt Mask */ +#define UART_IM_RTIM (1 << 6) /* Bit 6: UART Receive Time-Out Interrupt Mask */ +#define UART_IM_FEIM (1 << 7) /* Bit 7: UART Framing Error Interrupt Mask */ +#define UART_IM_PEIM (1 << 8) /* Bit 8: UART Parity Error Interrupt Mask */ +#define UART_IM_BEIM (1 << 9) /* Bit 9: UART Break Error Interrupt Mask */ +#define UART_IM_OEIM (1 << 10) /* Bit 10: UART Overrun Error Interrupt Mask */ + + +/* UART Raw Interrupt Status (RIS), offset 0x03c */ + +#define UART_RIS_RXRIS (1 << 4) /* Bit 4: UART Receive Raw Interrupt Status */ +#define UART_RIS_TXRIS (1 << 5) /* Bit 5: UART Transmit Raw Interrupt Status */ +#define UART_RIS_RTRIS (1 << 6) /* Bit 6: UART Receive Time-Out Raw Interrupt Status */ +#define UART_RIS_FERIS (1 << 7) /* Bit 7: UART Framing Error Raw Interrupt Status */ +#define UART_RIS_PERIS (1 << 8) /* Bit 8: UART Parity Error Raw Interrupt Status */ +#define UART_RIS_BERIS (1 << 9) /* Bit 9: UART Break Error Raw Interrupt Status */ +#define UART_RIS_OERIS (1 << 10) /* Bit 10: UART Overrun Error Raw Interrupt Status */ + +/* UART Masked Interrupt Status (MIS), offset 0x040 */ + +#define UART_MIS_RXMIS (1 << 4) /* Bit 4: UART Receive Masked Interrupt Status */ +#define UART_MIS_TXMIS (1 << 5) /* Bit 5: UART Transmit Masked Interrupt Status */ +#define UART_MIS_RTMIS (1 << 6) /* Bit 6: UART Receive Time-Out Masked Interrupt Status */ +#define UART_MIS_FEMIS (1 << 7) /* Bit 7: UART Framing Error Masked Interrupt Status */ +#define UART_MIS_PEMIS (1 << 8) /* Bit 8: UART Parity Error Masked Interrupt Status */ +#define UART_MIS_BEMIS (1 << 9) /* Bit 9: UART Break Error Masked Interrupt Status */ +#define UART_MIS_OEMIS (1 << 10) /* Bit 10: UART Overrun Error Masked Interrupt Status */ + +/* UART Interrupt Clear (ICR), offset 0x044 */ + +#define UART_ICR_RXIC (1 << 4) /* Bit 4: Receive Interrupt Clear */ +#define UART_ICR_TXIC (1 << 5) /* Bit 5: Transmit Interrupt Clear */ +#define UART_ICR_RTIC (1 << 6) /* Bit 6: Receive Time-Out Interrupt Clear */ +#define UART_ICR_FEIC (1 << 7) /* Bit 7: Framing Error Interrupt Clear */ +#define UART_ICR_PEIC (1 << 8) /* Bit 8: Parity Error Interrupt Clear */ +#define UART_ICR_BEIC (1 << 9) /* Bit 9: Break Error Interrupt Clear */ +#define UART_ICR_OEIC (1 << 10) /* Bit 10: Overrun Error Interrupt Clear + */ + +/* UART Peripheral Identification 4 (PERIPHID4), offset 0xfd0 */ + +#define UART_PERIPHID4_MASK (0xff) /* UART Peripheral ID Register[7:0] */ + +/* UART Peripheral Identification 5 (UARTPERIPHID5), offset 0xfd4 */ + +#define UART_PERIPHID5_MASK (0xff) /* UART Peripheral ID Register[15:8] */ + +/* UART Peripheral Identification 6 (UARTPERIPHID6), offset 0xfd8 */ + +#define UART_PERIPHID6_MASK (0xff) /* UART Peripheral ID Register[23:16] */ + +/* UART Peripheral Identification 7 (UARTPERIPHID7), offset 0xfdc */ + +#define UART_PERIPHID7_MASK (0xff) /* UART Peripheral ID Register[31:24] */ + +/* UART Peripheral Identification 0 (UARTPERIPHID0), offset 0xfe0 */ + +#define UART_PERIPHID0_MASK (0xff) /* UART Peripheral ID Register[7:0] */ + +/* UART Peripheral Identification 1 (UARTPERIPHID1), offset 0xfe4 */ + +#define UART_PERIPHID1_MASK (0xff) /* UART Peripheral ID Register[15:8] */ + +/* UART Peripheral Identification 2 (UARTPERIPHID2), offset 0xfe8 */ + +#define UART_PERIPHID2_MASK (0xff) /* UART Peripheral ID Register[23:16] */ + +/* UART Peripheral Identification 3 (UARTPERIPHID3), offset 0xfec */ + +#define UART_PERIPHID3_MASK (0xff) /* UART Peripheral ID Register[31:24] */ + +/* UART PrimeCell Identification 0 (CELLID0), offset 0xff0 */ + +#define UART_CELLID0_MASK (0xff) /* UART PrimeCell ID Register[7:0] */ + +/* UART PrimeCell Identification 1 (UARTPCELLID1), offset 0xff4 */ + +#define UART_CELLID1_MASK (0xff) /* UART PrimeCell ID Register[15:8] */ + +/* UART PrimeCell Identification 2 (UARTPCELLID2), offset 0xff8 */ + +#define UART_CELLID02MASK (0xff) /* UART PrimeCell ID Register[23:16] */ + +/* UART PrimeCell Identification 3 (UARTPCELLID3), offset 0xffc */ + +#define UART_CELLID3_MASK (0xff) /* UART PrimeCell ID Register[31:24] */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_UART_H */ diff --git a/nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h b/nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h new file mode 100644 index 000000000..c52857847 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h @@ -0,0 +1,69 @@ +/************************************************************************************ + * arch/arm/src/lm3s/chip/lm_memorymap.h + * + * Copyright (C) 2013 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_CHIP_LM_MEMORYMAP_H +#define __ARCH_ARM_SRC_LM3S_CHIP_LM_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/* Include the memory map file for the specific Stellaris chip */ + +#ifdef CONFIG_ARCH_CHIP_LM3S +# include "chip/lm3s_memorymap.h" +#else +# error "Unsupported Stellaris memory map" +#endif + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_epi.h b/nuttx/arch/arm/src/lm3s/lm3s_epi.h deleted file mode 100644 index 90c9bfb7f..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_epi.h +++ /dev/null @@ -1,113 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_epi.h - * - * Copyright (C) 2009-2012 Max Neklyudov. All rights reserved. - * Author: Max Neklyudov - * - * 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_EPI_H -#define __ARCH_ARM_SRC_LM3S_LM3S_EPI_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* External Peripheral Interface Register Offsets ***********************************/ - -#define LM3S_EPI_CFG_OFFSET 0x000 -#define LM3S_EPI_SDRAMCFG_OFFSET 0x010 -#define LM3S_EPI_ADDRMAP_OFFSET 0x01C -#define LM3S_EPI_STAT_OFFSET 0x060 -#define LM3S_EPI_BAUD_OFFSET 0x004 - -/* External Peripheral Interface Register Addresses *********************************/ - -#define LM3S_EPI0_CFG (LM3S_EPI0_BASE + LM3S_EPI_CFG_OFFSET) -#define LM3S_EPI0_SDRAMCFG (LM3S_EPI0_BASE + LM3S_EPI_SDRAMCFG_OFFSET) -#define LM3S_EPI0_ADDRMAP (LM3S_EPI0_BASE + LM3S_EPI_ADDRMAP_OFFSET) -#define LM3S_EPI0_STAT (LM3S_EPI0_BASE + LM3S_EPI_STAT_OFFSET) -#define LM3S_EPI0_BAUD (LM3S_EPI0_BASE + LM3S_EPI_BAUD_OFFSET) - -/* External Peripheral Interface Register Bit Definitions ***************************/ - -/* EPI Configuration (EPICFG), offset 0x000 */ - -#define EPI_CFG_MODE_SHIFT 0 /* Bits 3-0: Mode Select */ -#define EPI_CFG_MODE_MASK (0x1f << EPI_CFG_MODE_SHIFT) -# define EPI_CFG_MODE_SDRAM (0x11 << EPI_CFG_MODE_SHIFT) /* SDRAM + BLKEN */ - -/* EPI Address Map (EPIADDRMAP), offset 0x01C */ - -#define EPI_ADDRMAP_ERADR_SHIFT 0 /* Bits 1-0: External RAM Address */ -#define EPI_ADDRMAP_ERADR_MASK (0x3 << EPI_ADDRMAP_ERADR_SHIFT) -# define EPI_ADDRMAP_ERADR_6 (0x1 << EPI_ADDRMAP_ERADR_SHIFT) -# define EPI_ADDRMAP_ERADR_8 (0x2 << EPI_ADDRMAP_ERADR_SHIFT) -#define EPI_ADDRMAP_ERSZ_SHIFT 2 /* Bits 3-2: External RAM Size */ -#define EPI_ADDRMAP_ERSZ_MASK (0x3 << EPI_ADDRMAP_ERSZ_SHIFT) -# define EPI_ADDRMAP_ERSZ_256B (0x0 << EPI_ADDRMAP_ERSZ_SHIFT) -# define EPI_ADDRMAP_ERSZ_64KB (0x1 << EPI_ADDRMAP_ERSZ_SHIFT) -# define EPI_ADDRMAP_ERSZ_16MB (0x2 << EPI_ADDRMAP_ERSZ_SHIFT) -# define EPI_ADDRMAP_ERSZ_512MB (0x3 << EPI_ADDRMAP_ERSZ_SHIFT) - -/* EPI Status (EPISTAT), offset 0x060 */ - -#define EPI_STAT_INITSEQ_SHIFT 6 /* Bits 6: Initialization Sequence */ -#define EPI_STAT_INITSEQ_MASK (0x1 << EPI_STAT_INITSEQ_SHIFT) - -/* EPI SDRAM Configuration (EPISDRAMCFG), offset 0x010 */ - -#define EPI_SDRAMCFG_SIZE_SHIFT 0 /* Bits 1-0: Size of SDRAM */ -#define EPI_SDRAMCFG_SIZE_MASK (3 << EPI_SDRAMCFG_SIZE_SHIFT) -# define EPI_SDRAMCFG_SIZE_8MB (0x0 << EPI_SDRAMCFG_SIZE_SHIFT) -# define EPI_SDRAMCFG_SIZE_16MB (0x1 << EPI_SDRAMCFG_SIZE_SHIFT) -# define EPI_SDRAMCFG_SIZE_32MB (0x2 << EPI_SDRAMCFG_SIZE_SHIFT) -# define EPI_SDRAMCFG_SIZE_64MB (0x3 << EPI_SDRAMCFG_SIZE_SHIFT) -#define EPI_SDRAMCFG_RFSH_SHIFT 16 /* Bits 26-16: Refresh Counter */ -#define EPI_SDRAMCFG_RFSH_MASK (0x7FF << EPI_SDRAMCFG_RFSH_SHIFT) -# define EPI_SDRAMCFG_RFSH(n) ((n) << EPI_SDRAMCFG_RFSH_SHIFT) -#define EPI_SDRAMCFG_FREQ_SHIFT 30 /* EPI Frequency Range */ -#define EPI_SDRAMCFG_FREQ_MASK (3 << EPI_SDRAMCFG_FREQ_SHIFT) -# define EPI_SDRAMCFG_FREQ_0_15MHZ (0x0 << EPI_SDRAMCFG_FREQ_SHIFT) -# define EPI_SDRAMCFG_FREQ_15_30MHZ (0x1 << EPI_SDRAMCFG_FREQ_SHIFT) -# define EPI_SDRAMCFG_FREQ_30_50MHZ (0x2 << EPI_SDRAMCFG_FREQ_SHIFT) -# define EPI_SDRAMCFG_FREQ_50_100MHZ (0x3 << EPI_SDRAMCFG_FREQ_SHIFT) - -/* EPI Main Baud Rate (EPIBAUD), offset 0x004 */ - -#define EPI_BAUD_COUNT0_SHIFT 0 -#define EPI_BAUD_COUNT0_MASK (0xFFFF << EPI_BAUD_COUNT0_SHIFT) -# define EPI_BAUD_COUNT0(n) ((n) << EPI_BAUD_COUNT0_SHIFT) - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_EPI_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h deleted file mode 100644 index 71833b271..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h +++ /dev/null @@ -1,203 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_ethernet.h - * - * Copyright (C) 2009-2010, 2012 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_ETHERNET_H -#define __ARCH_ARM_SRC_LM3S_LM3S_ETHERNET_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include - -#include "chip.h" - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* Ethernet Controller Register Offsets *********************************************/ - -/* Ethernet MAC Register Offsets */ - -#define LM3S_MAC_RIS_OFFSET 0x000 /* Ethernet MAC Raw Interrupt Status */ -#define LM3S_MAC_IACK_OFFSET 0x000 /* Ethernet MAC Acknowledge */ -#define LM3S_MAC_IM_OFFSET 0x004 /* Ethernet MAC Interrupt Mask */ -#define LM3S_MAC_RCTL_OFFSET 0x008 /* Ethernet MAC Receive Control */ -#define LM3S_MAC_TCTL_OFFSET 0x00c /* Ethernet MAC Transmit Control */ -#define LM3S_MAC_DATA_OFFSET 0x010 /* Ethernet MAC Data */ -#define LM3S_MAC_IA0_OFFSET 0x014 /* Ethernet MAC Individual Address 0 */ -#define LM3S_MAC_IA1_OFFSET 0x018 /* Ethernet MAC Individual Address 1 */ -#define LM3S_MAC_THR_OFFSET 0x01c /* Ethernet MAC Threshold */ -#define LM3S_MAC_MCTL_OFFSET 0x020 /* Ethernet MAC Management Control */ -#define LM3S_MAC_MDV_OFFSET 0x024 /* Ethernet MAC Management Divider */ -#define LM3S_MAC_MTXD_OFFSET 0x02c /* Ethernet MAC Management Transmit Data */ -#define LM3S_MAC_MRXD_OFFSET 0x030 /* Ethernet MAC Management Receive Data */ -#define LM3S_MAC_NP_OFFSET 0x034 /* Ethernet MAC Number of Packets */ -#define LM3S_MAC_TR_OFFSET 0x038 /* Ethernet MAC Transmission Request */ -#ifdef LM3S_ETHTS -# define LM3S_MAC_TS_OFFSET 0x03c /* Ethernet MAC Time Stamp Configuration */ -#endif - -/* MII Management Register Offsets (see include/nuttx/net/mii.h) */ - -/* Ethernet Controller Register Addresses *******************************************/ - -#define LM3S_MAC_RIS (LM3S_ETHCON_BASE + LM3S_MAC_RIS_OFFSET) -#define LM3S_MAC_IACK (LM3S_ETHCON_BASE + LM3S_MAC_IACK_OFFSET) -#define LM3S_MAC_IM (LM3S_ETHCON_BASE + LM3S_MAC_IM_OFFSET) -#define LM3S_MAC_RCTL (LM3S_ETHCON_BASE + LM3S_MAC_RCTL_OFFSET) -#define LM3S_MAC_TCTL (LM3S_ETHCON_BASE + LM3S_MAC_TCTL_OFFSET) -#define LM3S_MAC_DATA (LM3S_ETHCON_BASE + LM3S_MAC_DATA_OFFSET) -#define LM3S_MAC_IA0 (LM3S_ETHCON_BASE + LM3S_MAC_IA0_OFFSET) -#define LM3S_MAC_IA1 (LM3S_ETHCON_BASE + LM3S_MAC_IA1_OFFSET) -#define LM3S_MAC_THR (LM3S_ETHCON_BASE + LM3S_MAC_THR_OFFSET) -#define LM3S_MAC_MCTL (LM3S_ETHCON_BASE + LM3S_MAC_MCTL_OFFSET) -#define LM3S_MAC_MDV (LM3S_ETHCON_BASE + LM3S_MAC_MDV_OFFSET) -#define LM3S_MAC_MTXD (LM3S_ETHCON_BASE + LM3S_MAC_MTXD_OFFSET) -#define LM3S_MAC_MRXD (LM3S_ETHCON_BASE + LM3S_MAC_MRXD_OFFSET) -#define LM3S_MAC_NP (LM3S_ETHCON_BASE + LM3S_MAC_NP_OFFSET) -#define LM3S_MAC_TR (LM3S_ETHCON_BASE + LM3S_MAC_TR_OFFSET) -#ifdef LM3S_ETHTS -# define LM3S_MAC_TS (LM3S_ETHCON_BASE + LM3S_MAC_TS_OFFSET) -#endif - -/* Memory Mapped MII Management Registers */ - -#define MAC_MII_MCR (LM3S_ETHCON_BASE + MII_MCR) -#define MAC_MII_MSR (LM3S_ETHCON_BASE + MII_MSR) -#define MAC_MII_PHYID1 (LM3S_ETHCON_BASE + MII_PHYID1) -#define MAC_MII_PHYID2 (LM3S_ETHCON_BASE + MII_PHYID2) -#define MAC_MII_ADVERTISE (LM3S_ETHCON_BASE + MII_ADVERTISE) -#define MAC_MII_LPA (LM3S_ETHCON_BASE + MII_LPA) -#define MAC_MII_EXPANSION (LM3S_ETHCON_BASE + MII_EXPANSION) -#define MAC_MII_VSPECIFIC (LM3S_ETHCON_BASE + MII_LM3S_VSPECIFIC) -#define MAC_MII_INTCS (LM3S_ETHCON_BASE + MII_LM3S_INTCS) -#define MAC_MII_DIAGNOSTIC (LM3S_ETHCON_BASE + MII_LM3S_DIAGNOSTIC) -#define MAC_MII_XCVRCONTROL (LM3S_ETHCON_BASE + MII_LM3S_XCVRCONTROL) -#define MAC_MII_LEDCONFIG (LM3S_ETHCON_BASE + MII_LM3S_LEDCONFIG) -#define MAC_MII_MDICONTROL (LM3S_ETHCON_BASE + MII_LM3S_MDICONTROL) - -/* Ethernet Controller Register Bit Definitions *************************************/ - -/* Ethernet MAC Raw Interrupt Status/Acknowledge (MACRIS/MACIACK), offset 0x000 */ - -#define MAC_RIS_RXINT (1 << 0) /* Bit 0: Packet Received */ -#define MAC_RIS_TXER (1 << 1) /* Bit 1: Transmit Error */ -#define MAC_RIS_TXEMP (1 << 2) /* Bit 2: Transmit FIFO Empty */ -#define MAC_RIS_FOV (1 << 3) /* Bit 3: FIFO Overrun */ -#define MAC_RIS_RXER (1 << 4) /* Bit 4: Receive Error */ -#define MAC_RIS_MDINT (1 << 5) /* Bit 5: MII Transaction Complete */ -#define MAC_RIS_PHYINT (1 << 6) /* Bit 6: PHY Interrupt */ - -#define MAC_IACK_RXINT (1 << 0) /* Bit 0: Clear Packet Received */ -#define MAC_IACK_TXER (1 << 1) /* Bit 1: Clear Transmit Error */ -#define MAC_IACK_TXEMP (1 << 2) /* Bit 2: Clear Transmit FIFO Empty */ -#define MAC_IACK_FOV (1 << 3) /* Bit 3: Clear FIFO Overrun */ -#define MAC_IACK_RXER (1 << 4) /* Bit 4: Clear Receive Error */ -#define MAC_IACK_MDINT (1 << 5) /* Bit 5: Clear MII Transaction Complete */ -#define MAC_IACK_PHYINT (1 << 6) /* Bit 6: Clear PHY Interrupt */ - -/* Ethernet MAC Interrupt Mask (MACIM), offset 0x004 */ - -#define MAC_IM_RXINTM (1 << 0) /* Bit 0: Mask Packet Received */ -#define MAC_IM_TXERM (1 << 1) /* Bit 1: Mask Transmit Error */ -#define MAC_IM_TXEMPM (1 << 2) /* Bit 2: Mask Transmit FIFO Empty */ -#define MAC_IM_FOVM (1 << 3) /* Bit 3: Mask FIFO Overrun */ -#define MAC_IM_RXERM (1 << 4) /* Bit 4: Mask Receive Error */ -#define MAC_IM_MDINTM (1 << 5) /* Bit 5: Mask MII Transaction Complete */ -#define MAC_IM_PHYINTM (1 << 6) /* Bit 6: Mask PHY Interrupt */ -#define MAC_IM_ALLINTS 0x7f - -/* Ethernet MAC Receive Control (MACRCTL), offset 0x008 */ - -#define MAC_RCTL_RXEN (1 << 0) /* Bit 0: Enable Receiver */ -#define MAC_RCTL_AMUL (1 << 1) /* Bit 1: Enable Multicast Frames */ -#define MAC_RCTL_PRMS (1 << 2) /* Bit 2: Enable Promiscuous Mode */ -#define MAC_RCTL_BADCRC (1 << 3) /* Bit 3: Enable Reject Bad CRC */ -#define MAC_RCTL_RSTFIFO (1 << 4) /* Bit 4: Clear Receive FIFO */ - -/* Ethernet MAC Transmit Control (MACTCTL), offset 0x00c */ - -#define MAC_TCTL_TXEN (1 << 0) /* Bit 0: Enable Transmitter */ -#define MAC_TCTL_PADEN (1 << 1) /* Bit 1: Enable Packet Padding */ -#define MAC_TCTL_CRC (1 << 2) /* Bit 2: Enable CRC Generation */ -#define MAC_TCTL_DUPLEX (1 << 4) /* Bit 4: Enable Duplex Mode */ - -/* Ethernet MAC Threshold (MACTHR), offset 0x01c */ - -#define MAC_THR_MASK 0x3f /* Bits 5-0: Threshold Value */ - -/* Ethernet MAC Management Control (MACMCTL), offset 0x020 */ - -#define MAC_MCTL_START (1 << 0) /* Bit 0: MII Register Transaction Enable */ -#define MAC_MCTL_WRITE (1 << 1) /* Bit 1: MII Register Transaction Type */ -#define MAC_MCTL_REGADR_SHIFT 3 /* Bits 7-3: MII Register Address */ -#define MAC_MCTL_REGADR_MASK (0x1f << MAC_MCTL_REGADR_SHIFT) - -/* Ethernet MAC Management Divider (MACMDV), offset 0x024 */ - -#define MAC_MDV_MASK 0xff /* Bits 7-0: Clock Divider */ - -/* Ethernet MAC Management Transmit Data (MACTXD), offset 0x02c */ - -#define MAC_MTXD_MASK 0xffff /* Bits 15-0: MII Register Transmit Data */ - -/* Ethernet MAC Management Receive Data (MACRXD), offset 0x030 */ - -#define MAC_MTRD_MASK 0xffff /* Bits 15-0: MII Register Receive Data */ - -/* Ethernet MAC Number of Packets (MACNP), offset 0x034 */ - -#define MAC_NP_MASK 0x3f /* Bits 5-0: Number of Packets in Receive FIFO */ - -/* Ethernet MAC Transmission Request (MACTR), offset 0x038 */ - -#define MAC_TR_NEWTX (1 << 0) /* Bit 0: New Transmission */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_ETHERNET_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_flash.h b/nuttx/arch/arm/src/lm3s/lm3s_flash.h deleted file mode 100644 index 83e388921..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_flash.h +++ /dev/null @@ -1,128 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_flash.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_FLASH_H -#define __ARCH_ARM_SRC_LM3S_LM3S_FLASH_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* FLASH register offsets ***********************************************************/ - -/* The FMA, FMD, FMC, FCRIS, FCIM, and FCMISC registers are relative to the Flash - * control base address of LM3S_FLASHCON_BASE. - */ - -#define LM3S_FLASH_FMA_OFFSET 0x000 /* Flash memory address */ -#define LM3S_FLASH_FMD_OFFSET 0x004 /* Flash memory data */ -#define LM3S_FLASH_FMC_OFFSET 0x008 /* Flash memory control */ -#define LM3S_FLASH_FCRIS_OFFSET 0x00c /* Flash controller raw interrupt status */ -#define LM3S_FLASH_FCIM_OFFSET 0x010 /* Flash controller interrupt mask */ -#define LM3S_FLASH_FCMISC_OFFSET 0x014 /* Flash controller masked interrupt status and clear */ */ - -/* The FMPREn, FMPPEn, USECRL, USER_DBG, and USER_REGn registers are relative to the - * System Control base address of LM3S_SYSCON_BASE - */ - -#define LM3S_FLASH_FMPRE_OFFSET 0x130 /* Flash memory protection read enable */ -#define LM3S_FLASH_FMPPE_OFFSET 0x134 /* Flash memory protection program enable */ -#define LM3S_FLASH_USECRL_OFFSET 0x140 /* USec Reload */ -#define LM3S_FLASH_USERDBG_OFFSET 0x1d0 /* User Debug */ -#define LM3S_FLASH_USERREG0_OFFSET 0x1e0 /* User Register 0 */ -#define LM3S_FLASH_USERREG1_OFFSET 0x1e4 /* User Register 1 */ -#define LM3S_FLASH_FMPRE0_OFFSET 0x200 /* Flash Memory Protection Read Enable 0 */ -#define LM3S_FLASH_FMPRE1_OFFSET 0x204 /* Flash Memory Protection Read Enable 1 */ -#define LM3S_FLASH_FMPRE2_OFFSET 0x208 /* Flash Memory Protection Read Enable 2 */ -#define LM3S_FLASH_FMPRE3_OFFSET 0x20c /* Flash Memory Protection Read Enable 3 */ -#define LM3S_FLASH_FMPPE0_OFFSET 0x400 /* Flash Memory Protection Program Enable 0 */ -#define LM3S_FLASH_FMPPE1_OFFSET 0x404 /* Flash Memory Protection Program Enable 1 */ -#define LM3S_FLASH_FMPPE2_OFFSET 0x408 /* Flash Memory Protection Program Enable 2 */ -#define LM3S_FLASH_FMPPE3_OFFSET 0x40c /* Flash Memory Protection Program Enable 3 */ - -/* FLASH register addresses *********************************************************/ - -/* The FMA, FMD, FMC, FCRIS, FCIM, and FCMISC registers are relative to the Flash - * control base address of LM3S_FLASHCON_BASE. - */ - -#define LM3S_FLASH_FMA (LM3S_FLASHCON_BASE + LM3S_FLASH_FMA_OFFSET) -#define LM3S_FLASH_FMD (LM3S_FLASHCON_BASE + LM3S_FLASH_FMD_OFFSET) -#define LM3S_FLASH_FMC (LM3S_FLASHCON_BASE + LM3S_FLASH_FMC_OFFSET) -#define LM3S_FLASH_FCRIS (LM3S_FLASHCON_BASE + LM3S_FLASH_FCRIS_OFFSET) -#define LM3S_FLASH_FCIM (LM3S_FLASHCON_BASE + LM3S_FLASH_FCIM_OFFSET) -#define LM3S_FLASH_FCMISC (LM3S_FLASHCON_BASE + LM3S_FLASH_FCMISC_OFFSET) - -/* The FMPREn, FMPPEn, USECRL, USER_DBG, and USER_REGn registers are relative to the - * System Control base address of LM3S_SYSCON_BASE - */ - -#define LM3S_FLASH_FMPRE (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE_OFFSET) -#define LM3S_FLASH_FMPPE (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE_OFFSET) -#define LM3S_FLASH_USECRL (LM3S_SYSCON_BASE + LM3S_FLASH_USECRL_OFFSET) -#define LM3S_FLASH_USERDBG (LM3S_SYSCON_BASE + LM3S_FLASH_USERDBG_OFFSET) -#define LM3S_FLASH_USERREG0 (LM3S_SYSCON_BASE + LM3S_FLASH_USERREG0_OFFSET) -#define LM3S_FLASH_USERREG1 (LM3S_SYSCON_BASE + LM3S_FLASH_USERREG1_OFFSET) -#define LM3S_FLASH_FMPRE0 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE0_OFFSET) -#define LM3S_FLASH_FMPRE1 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE1_OFFSET) -#define LM3S_FLASH_FMPRE2 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE2_OFFSET) -#define LM3S_FLASH_FMPRE3 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPRE3_OFFSET) -#define LM3S_FLASH_FMPPE0 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE0_OFFSET) -#define LM3S_FLASH_FMPPE1 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE1_OFFSET) -#define LM3S_FLASH_FMPPE2 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE2_OFFSET) -#define LM3S_FLASH_FMPPE3 (LM3S_SYSCON_BASE + LM3S_FLASH_FMPPE3_OFFSET) - -/* FLASH register bit defitiions ****************************************************/ -/* To be provided */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_FLASH_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h b/nuttx/arch/arm/src/lm3s/lm3s_gpio.h deleted file mode 100644 index 066666432..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h +++ /dev/null @@ -1,395 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_gpio.h - * - * Copyright (C) 2009-2010 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_GPIO_H -#define __ARCH_ARM_SRC_LM3S_LM3S_GPIO_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* GPIO Register Offsets ************************************************************/ - -#define LM3S_GPIO_DATA_OFFSET 0x000 /* GPIO Data */ -#define LM3S_GPIO_DIR_OFFSET 0x400 /* GPIO Direction */ -#define LM3S_GPIO_IS_OFFSET 0x404 /* GPIO Interrupt Sense */ -#define LM3S_GPIO_IBE_OFFSET 0x408 /* GPIO Interrupt Both Edges */ -#define LM3S_GPIO_IEV_OFFSET 0x40c /* GPIO Interrupt Event */ -#define LM3S_GPIO_IM_OFFSET 0x410 /* GPIO Interrupt Mask */ -#define LM3S_GPIO_RIS_OFFSET 0x414 /* GPIO Raw Interrupt Status */ -#define LM3S_GPIO_MIS_OFFSET 0x418 /* GPIO Masked Interrupt Status */ -#define LM3S_GPIO_ICR_OFFSET 0x41c /* GPIO Interrupt Clear */ -#define LM3S_GPIO_AFSEL_OFFSET 0x420 /* GPIO Alternate Function */ -#define LM3S_GPIO_DR2R_OFFSET 0x500 /* Select GPIO 2-mA Drive Select */ -#define LM3S_GPIO_DR4R_OFFSET 0x504 /* GPIO 4-mA Drive Select */ -#define LM3S_GPIO_DR8R_OFFSET 0x508 /* GPIO 8-mA Drive Select */ -#define LM3S_GPIO_ODR_OFFSET 0x50c /* GPIO Open Drain Select */ -#define LM3S_GPIO_PUR_OFFSET 0x510 /* GPIO Pull-Up Select */ -#define LM3S_GPIO_PDR_OFFSET 0x514 /* GPIO Pull-Down Select */ -#define LM3S_GPIO_SLR_OFFSET 0x518 /* GPIO Slew Rate Control Select */ -#define LM3S_GPIO_DEN_OFFSET 0x51C /* GPIO Digital Enable */ -#define LM3S_GPIO_LOCK_OFFSET 0x520 /* GPIO Lock */ -#define LM3S_GPIO_CR_OFFSET 0x524 /* GPIO Commit */ -#define LM3S_GPIO_PERIPHID4_OFFSET 0xfd0 /* GPIO Peripheral Identification 4 */ -#define LM3S_GPIO_PERIPHID5_OFFSET 0xfd4 /* GPIO Peripheral Identification 5 */ -#define LM3S_GPIO_PERIPHID6_OFFSET 0xfd8 /* GPIO Peripheral Identification 6 */ -#define LM3S_GPIO_PERIPHID7_OFFSET 0xfdc /* GPIO Peripheral Identification 7 */ -#define LM3S_GPIO_PERIPHID0_OFFSET 0xfe0 /* GPIO Peripheral Identification 0 */ -#define LM3S_GPIO_PERIPHID1_OFFSET 0xfe4 /* GPIO Peripheral Identification 1 */ -#define LM3S_GPIO_PERIPHID2_OFFSET 0xfe8 /* GPIO Peripheral Identification 2 */ -#define LM3S_GPIO_PERIPHID3_OFFSET 0xfec /* GPIO Peripheral Identification 3 */ -#define LM3S_GPIO_PCELLID0_OFFSET 0xff0 /* GPIO PrimeCell Identification 0 */ -#define LM3S_GPIO_PCELLID1_OFFSET 0xff4 /* GPIO PrimeCell Identification 1 */ -#define LM3S_GPIO_PCELLID2_OFFSET 0xff8 /* GPIO PrimeCell Identification 2 */ -#define LM3S_GPIO_PCELLID3_OFFSET 0xffc /* GPIO PrimeCell Identification 3*/ - -/* GPIO Register Addresses **********************************************************/ - -#define LM3S_GPIOA_DATA (LM3S_GPIOA_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOA_DIR (LM3S_GPIOA_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOA_IS (LM3S_GPIOA_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOA_IBE (LM3S_GPIOA_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOA_IEV (LM3S_GPIOA_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOA_IM (LM3S_GPIOA_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOA_RIS (LM3S_GPIOA_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOA_MIS (LM3S_GPIOA_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOA_ICR (LM3S_GPIOA_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOA_AFSEL (LM3S_GPIOA_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOA_DR2R (LM3S_GPIOA_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOA_DR4R (LM3S_GPIOA_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOA_DR8R (LM3S_GPIOA_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOA_ODR (LM3S_GPIOA_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOA_PUR (LM3S_GPIOA_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOA_PDR (LM3S_GPIOA_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOA_SLR (LM3S_GPIOA_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOA_DEN (LM3S_GPIOA_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOA_LOCK (LM3S_GPIOA_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOA_CR (LM3S_GPIOA_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOA_PERIPHID4 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOA_PERIPHID5 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOA_PERIPHID6 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOA_PERIPHID7 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOA_PERIPHID0 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOA_PERIPHID1 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOA_PERIPHID2 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOA_PERIPHID3 (LM3S_GPIOA_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOA_PCELLID0 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOA_PCELLID1 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOA_PCELLID2 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOA_PCELLID3 (LM3S_GPIOA_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOB_DATA (LM3S_GPIOB_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOB_DIR (LM3S_GPIOB_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOB_IS (LM3S_GPIOB_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOB_IBE (LM3S_GPIOB_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOB_IEV (LM3S_GPIOB_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOB_IM (LM3S_GPIOB_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOB_RIS (LM3S_GPIOB_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOB_MIS (LM3S_GPIOB_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOB_ICR (LM3S_GPIOB_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOB_AFSEL (LM3S_GPIOB_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOB_DR2R (LM3S_GPIOB_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOB_DR4R (LM3S_GPIOB_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOB_DR8R (LM3S_GPIOB_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOB_ODR (LM3S_GPIOB_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOB_PUR (LM3S_GPIOB_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOB_PDR (LM3S_GPIOB_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOB_SLR (LM3S_GPIOB_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOB_DEN (LM3S_GPIOB_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOB_LOCK (LM3S_GPIOB_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOB_CR (LM3S_GPIOB_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOB_PERIPHID4 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOB_PERIPHID5 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOB_PERIPHID6 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOB_PERIPHID7 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOB_PERIPHID0 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOB_PERIPHID1 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOB_PERIPHID2 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOB_PERIPHID3 (LM3S_GPIOB_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOB_PCELLID0 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOB_PCELLID1 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOB_PCELLID2 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOB_PCELLID3 (LM3S_GPIOB_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOC_DATA (LM3S_GPIOC_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOC_DIR (LM3S_GPIOC_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOC_IS (LM3S_GPIOC_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOC_IBE (LM3S_GPIOC_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOC_IEV (LM3S_GPIOC_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOC_IM (LM3S_GPIOC_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOC_RIS (LM3S_GPIOC_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOC_MIS (LM3S_GPIOC_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOC_ICR (LM3S_GPIOC_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOC_AFSEL (LM3S_GPIOC_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOC_DR2R (LM3S_GPIOC_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOC_DR4R (LM3S_GPIOC_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOC_DR8R (LM3S_GPIOC_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOC_ODR (LM3S_GPIOC_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOC_PUR (LM3S_GPIOC_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOC_PDR (LM3S_GPIOC_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOC_SLR (LM3S_GPIOC_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOC_DEN (LM3S_GPIOC_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOC_LOCK (LM3S_GPIOC_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOC_CR (LM3S_GPIOC_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOC_PERIPHID4 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOC_PERIPHID5 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOC_PERIPHID6 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOC_PERIPHID7 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOC_PERIPHID0 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOC_PERIPHID1 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOC_PERIPHID2 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOC_PERIPHID3 (LM3S_GPIOC_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOC_PCELLID0 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOC_PCELLID1 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOC_PCELLID2 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOC_PCELLID3 (LM3S_GPIOC_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOD_DATA (LM3S_GPIOD_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOD_DIR (LM3S_GPIOD_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOD_IS (LM3S_GPIOD_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOD_IBE (LM3S_GPIOD_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOD_IEV (LM3S_GPIOD_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOD_IM (LM3S_GPIOD_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOD_RIS (LM3S_GPIOD_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOD_MIS (LM3S_GPIOD_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOD_ICR (LM3S_GPIOD_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOD_AFSEL (LM3S_GPIOD_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOD_DR2R (LM3S_GPIOD_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOD_DR4R (LM3S_GPIOD_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOD_DR8R (LM3S_GPIOD_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOD_ODR (LM3S_GPIOD_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOD_PUR (LM3S_GPIOD_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOD_PDR (LM3S_GPIOD_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOD_SLR (LM3S_GPIOD_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOD_DEN (LM3S_GPIOD_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOD_LOCK (LM3S_GPIOD_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOD_CR (LM3S_GPIOD_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOD_PERIPHID4 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOD_PERIPHID5 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOD_PERIPHID6 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOD_PERIPHID7 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOD_PERIPHID0 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOD_PERIPHID1 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOD_PERIPHID2 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOD_PERIPHID3 (LM3S_GPIOD_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOD_PCELLID0 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOD_PCELLID1 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOD_PCELLID2 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOD_PCELLID3 (LM3S_GPIOD_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOE_DATA (LM3S_GPIOE_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOE_DIR (LM3S_GPIOE_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOE_IS (LM3S_GPIOE_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOE_IBE (LM3S_GPIOE_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOE_IEV (LM3S_GPIOE_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOE_IM (LM3S_GPIOE_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOE_RIS (LM3S_GPIOE_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOE_MIS (LM3S_GPIOE_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOE_ICR (LM3S_GPIOE_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOE_AFSEL (LM3S_GPIOE_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOE_DR2R (LM3S_GPIOE_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOE_DR4R (LM3S_GPIOE_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOE_DR8R (LM3S_GPIOE_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOE_ODR (LM3S_GPIOE_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOE_PUR (LM3S_GPIOE_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOE_PDR (LM3S_GPIOE_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOE_SLR (LM3S_GPIOE_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOE_DEN (LM3S_GPIOE_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOE_LOCK (LM3S_GPIOE_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOE_CR (LM3S_GPIOE_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOE_PERIPHID4 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOE_PERIPHID5 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOE_PERIPHID6 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOE_PERIPHID7 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOE_PERIPHID0 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOE_PERIPHID1 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOE_PERIPHID2 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOE_PERIPHID3 (LM3S_GPIOE_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOE_PCELLID0 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOE_PCELLID1 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOE_PCELLID2 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOE_PCELLID3 (LM3S_GPIOE_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOF_DATA (LM3S_GPIOF_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOF_DIR (LM3S_GPIOF_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOF_IS (LM3S_GPIOF_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOF_IBE (LM3S_GPIOF_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOF_IEV (LM3S_GPIOF_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOF_IM (LM3S_GPIOF_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOF_RIS (LM3S_GPIOF_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOF_MIS (LM3S_GPIOF_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOF_ICR (LM3S_GPIOF_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOF_AFSEL (LM3S_GPIOF_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOF_DR2R (LM3S_GPIOF_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOF_DR4R (LM3S_GPIOF_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOF_DR8R (LM3S_GPIOF_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOF_ODR (LM3S_GPIOF_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOF_PUR (LM3S_GPIOF_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOF_PDR (LM3S_GPIOF_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOF_SLR (LM3S_GPIOF_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOF_DEN (LM3S_GPIOF_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOF_LOCK (LM3S_GPIOF_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOF_CR (LM3S_GPIOF_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOF_PERIPHID4 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOF_PERIPHID5 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOF_PERIPHID6 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOF_PERIPHID7 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOF_PERIPHID0 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOF_PERIPHID1 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOF_PERIPHID2 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOF_PERIPHID3 (LM3S_GPIOF_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOF_PCELLID0 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOF_PCELLID1 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOF_PCELLID2 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOF_PCELLID3 (LM3S_GPIOF_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOG_DATA (LM3S_GPIOG_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOG_DIR (LM3S_GPIOG_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOG_IS (LM3S_GPIOG_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOG_IBE (LM3S_GPIOG_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOG_IEV (LM3S_GPIOG_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOG_IM (LM3S_GPIOG_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOG_RIS (LM3S_GPIOG_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOG_MIS (LM3S_GPIOG_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOG_ICR (LM3S_GPIOG_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOG_AFSEL (LM3S_GPIOG_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOG_DR2R (LM3S_GPIOG_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOG_DR4R (LM3S_GPIOG_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOG_DR8R (LM3S_GPIOG_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOG_ODR (LM3S_GPIOG_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOG_PUR (LM3S_GPIOG_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOG_PDR (LM3S_GPIOG_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOG_SLR (LM3S_GPIOG_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOG_DEN (LM3S_GPIOG_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOG_LOCK (LM3S_GPIOG_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOG_CR (LM3S_GPIOG_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOG_PERIPHID4 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOG_PERIPHID5 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOG_PERIPHID6 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOG_PERIPHID7 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOG_PERIPHID0 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOG_PERIPHID1 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOG_PERIPHID2 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOG_PERIPHID3 (LM3S_GPIOG_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOG_PCELLID0 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOG_PCELLID1 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOG_PCELLID2 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOG_PCELLID3 (LM3S_GPIOG_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOH_DATA (LM3S_GPIOH_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOH_DIR (LM3S_GPIOH_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOH_IS (LM3S_GPIOH_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOH_IBE (LM3S_GPIOH_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOH_IEV (LM3S_GPIOH_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOH_IM (LM3S_GPIOH_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOH_RIS (LM3S_GPIOH_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOH_MIS (LM3S_GPIOH_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOH_ICR (LM3S_GPIOH_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOH_AFSEL (LM3S_GPIOH_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOH_DR2R (LM3S_GPIOH_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOH_DR4R (LM3S_GPIOH_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOH_DR8R (LM3S_GPIOH_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOH_ODR (LM3S_GPIOH_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOH_PUR (LM3S_GPIOH_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOH_PDR (LM3S_GPIOH_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOH_SLR (LM3S_GPIOH_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOH_DEN (LM3S_GPIOH_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOH_LOCK (LM3S_GPIOH_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOH_CR (LM3S_GPIOH_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOH_PERIPHID4 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOH_PERIPHID5 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOH_PERIPHID6 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOH_PERIPHID7 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOH_PERIPHID0 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOH_PERIPHID1 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOH_PERIPHID2 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOH_PERIPHID3 (LM3S_GPIOH_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOH_PCELLID0 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOH_PCELLID1 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOH_PCELLID2 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOH_PCELLID3 (LM3S_GPIOH_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -#define LM3S_GPIOJ_DATA (LM3S_GPIOJ_BASE + LM3S_GPIO_DATA_OFFSET) -#define LM3S_GPIOJ_DIR (LM3S_GPIOJ_BASE + LM3S_GPIO_DIR_OFFSET) -#define LM3S_GPIOJ_IS (LM3S_GPIOJ_BASE + LM3S_GPIO_IS_OFFSET) -#define LM3S_GPIOJ_IBE (LM3S_GPIOJ_BASE + LM3S_GPIO_IBE_OFFSET) -#define LM3S_GPIOJ_IEV (LM3S_GPIOJ_BASE + LM3S_GPIO_IEV_OFFSET) -#define LM3S_GPIOJ_IM (LM3S_GPIOJ_BASE + LM3S_GPIO_IM_OFFSET) -#define LM3S_GPIOJ_RIS (LM3S_GPIOJ_BASE + LM3S_GPIO_RIS_OFFSET) -#define LM3S_GPIOJ_MIS (LM3S_GPIOJ_BASE + LM3S_GPIO_MIS_OFFSET) -#define LM3S_GPIOJ_ICR (LM3S_GPIOJ_BASE + LM3S_GPIO_ICR_OFFSET) -#define LM3S_GPIOJ_AFSEL (LM3S_GPIOJ_BASE + LM3S_GPIO_AFSEL_OFFSET) -#define LM3S_GPIOJ_DR2R (LM3S_GPIOJ_BASE + LM3S_GPIO_DR2R_OFFSET) -#define LM3S_GPIOJ_DR4R (LM3S_GPIOJ_BASE + LM3S_GPIO_DR4R_OFFSET) -#define LM3S_GPIOJ_DR8R (LM3S_GPIOJ_BASE + LM3S_GPIO_DR8R_OFFSET) -#define LM3S_GPIOJ_ODR (LM3S_GPIOJ_BASE + LM3S_GPIO_ODR_OFFSET) -#define LM3S_GPIOJ_PUR (LM3S_GPIOJ_BASE + LM3S_GPIO_PUR_OFFSET) -#define LM3S_GPIOJ_PDR (LM3S_GPIOJ_BASE + LM3S_GPIO_PDR_OFFSET) -#define LM3S_GPIOJ_SLR (LM3S_GPIOJ_BASE + LM3S_GPIO_SLR_OFFSET) -#define LM3S_GPIOJ_DEN (LM3S_GPIOJ_BASE + LM3S_GPIO_DEN_OFFSET) -#define LM3S_GPIOJ_LOCK (LM3S_GPIOJ_BASE + LM3S_GPIO_LOCK_OFFSET) -#define LM3S_GPIOJ_CR (LM3S_GPIOJ_BASE + LM3S_GPIO_CR_OFFSET) -#define LM3S_GPIOJ_PERIPHID4 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID4_OFFSET) -#define LM3S_GPIOJ_PERIPHID5 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID5_OFFSET) -#define LM3S_GPIOJ_PERIPHID6 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID6_OFFSET) -#define LM3S_GPIOJ_PERIPHID7 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID7_OFFSET) -#define LM3S_GPIOJ_PERIPHID0 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID0_OFFSET) -#define LM3S_GPIOJ_PERIPHID1 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID1_OFFSET) -#define LM3S_GPIOJ_PERIPHID2 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID2_OFFSET) -#define LM3S_GPIOJ_PERIPHID3 (LM3S_GPIOJ_BASE + LM3S_GPIO_PERIPHID3_OFFSET) -#define LM3S_GPIOJ_PCELLID0 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID0_OFFSET) -#define LM3S_GPIOJ_PCELLID1 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID1_OFFSET) -#define LM3S_GPIOJ_PCELLID2 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID2_OFFSET) -#define LM3S_GPIOJ_PCELLID3 (LM3S_GPIOJ_BASE + LM3S_GPIO_PCELLID3_OFFSET) - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_GPIO_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_i2c.h b/nuttx/arch/arm/src/lm3s/lm3s_i2c.h deleted file mode 100644 index a5f0567b9..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_i2c.h +++ /dev/null @@ -1,247 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_i2c.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_I2C_H -#define __ARCH_ARM_SRC_LM3S_LM3S_I2C_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* I2C Register Offsets *************************************************************/ - -/* I2C Master */ - -#define LM3S_I2CM_SA_OFFSET 0x000 /* I2C Master Slave Address */ -#define LM3S_I2CM_CS_OFFSET 0x004 /* I2C Master Control/Status */ -#define LM3S_I2CM_DR_OFFSET 0x008 /* I2C Master Data */ -#define LM3S_I2CM_TPR_OFFSET 0x00c /* I2C Master Timer Period */ -#define LM3S_I2CM_IMR_OFFSET 0x010 /* I2C Master Interrupt Mask */ -#define LM3S_I2CM_RIS_OFFSET 0x014 /* I2C Master Raw Interrupt Status */ -#define LM3S_I2CM_MIS_OFFSET 0x018 /* I2C Master Masked Interrupt Status */ -#define LM3S_I2CM_ICR_OFFSET 0x01c /* I2C Master Interrupt Clear */ -#define LM3S_I2CM_CR_OFFSET 0x020 /* I2C Master Configuration */ - -/* I2C Slave */ - -#define LM3S_I2CS_OAR_OFFSET 0x000 /* I2C Slave Own Address */ -#define LM3S_I2CS_CSR_OFFSET 0x004 /* I2C Slave Control/Status */ -#define LM3S_I2CS_DR_OFFSET 0x008 /* I2C Slave Data */ -#define LM3S_I2CS_IMR_OFFSET 0x00c /* I2C Slave Interrupt Mask */ -#define LM3S_I2CS_RIS_OFFSET 0x010 /* I2C Slave Raw Interrupt Status */ -#define LM3S_I2CS_MIS_OFFSET 0x014 /* I2C Slave Masked Interrupt Status */ -#define LM3S_I2CS_ICR_OFFSET 0x018 /* I2C Slave Interrupt Clear */ - -/* I2C Register Addresses ***********************************************************/ - -#if LM3S_NI2C > 0 - -/* I2C Master */ - -#define LM3S_I2CM_BASE(n) (LM3S_I2CM0_BASE + (n)*0x1000) -#define LM3S_I2CM_SA(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_SA_OFFSET) -#define LM3S_I2CM_CS(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_CS_OFFSET) -#define LM3S_I2CM_DR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_DR_OFFSET) -#define LM3S_I2CM_TPR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_TPR_OFFSET) -#define LM3S_I2CM_IMR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_IMR_OFFSET) -#define LM3S_I2CM_RIS(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_RIS_OFFSET) -#define LM3S_I2CM_MIS(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_MIS_OFFSET) -#define LM3S_I2CM_ICR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_ICR_OFFSET) -#define LM3S_I2CM_CR(n) (LM3S_I2CM_BASE(n) + LM3S_I2CM_CR_OFFSET) - -/* I2C Slave */ - -#define LM3S_I2CS_BASE(n) (LM3S_I2CS0_BASE + (n)*0x1000) -#define LM3S_I2CS_OAR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_OAR_OFFSET) -#define LM3S_I2CS_CSR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_CSR_OFFSET) -#define LM3S_I2CS_DR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_DR_OFFSET) -#define LM3S_I2CS_IMR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_IMR_OFFSET) -#define LM3S_I2CS_RIS(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_RIS_OFFSET) -#define LM3S_I2CS_MIS(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_MIS_OFFSET) -#define LM3S_I2CS_ICR(n) (LM3S_I2CS_BASE(n) + LM3S_I2CS_ICR_OFFSET) - -/* I2C0 Master */ - -#define LM3S_I2CM0_SA (LM3S_I2CM0_BASE + LM3S_I2CM_SA_OFFSET) -#define LM3S_I2CM0_CS (LM3S_I2CM0_BASE + LM3S_I2CM_CS_OFFSET) -#define LM3S_I2CM0_DR (LM3S_I2CM0_BASE + LM3S_I2CM_DR_OFFSET) -#define LM3S_I2CM0_TPR (LM3S_I2CM0_BASE + LM3S_I2CM_TPR_OFFSET) -#define LM3S_I2CM0_IMR (LM3S_I2CM0_BASE + LM3S_I2CM_IMR_OFFSET) -#define LM3S_I2CM0_RIS (LM3S_I2CM0_BASE + LM3S_I2CM_RIS_OFFSET) -#define LM3S_I2CM0_MIS (LM3S_I2CM0_BASE + LM3S_I2CM_MIS_OFFSET) -#define LM3S_I2CM0_ICR (LM3S_I2CM0_BASE + LM3S_I2CM_ICR_OFFSET) -#define LM3S_I2CM0_CR (LM3S_I2CM0_BASE + LM3S_I2CM_CR_OFFSET) - -/* I2C0 Slave */ - -#define LM3S_I2CS0_OAR (LM3S_I2CS0_BASE + LM3S_I2CS_OAR_OFFSET) -#define LM3S_I2CS0_CSR (LM3S_I2CS0_BASE + LM3S_I2CS_CSR_OFFSET) -#define LM3S_I2CS0_DR (LM3S_I2CS0_BASE + LM3S_I2CS_DR_OFFSET) -#define LM3S_I2CS0_IMR (LM3S_I2CS0_BASE + LM3S_I2CS_IMR_OFFSET) -#define LM3S_I2CS0_RIS (LM3S_I2CS0_BASE + LM3S_I2CS_RIS_OFFSET) -#define LM3S_I2CS0_MIS (LM3S_I2CS0_BASE + LM3S_I2CS_MIS_OFFSET) -#define LM3S_I2CS0_ICR (LM3S_I2CS0_BASE + LM3S_I2CS_ICR_OFFSET) - -#if LM3S_NI2C > 1 - -/* I2C1 Master */ - -#define LM3S_I2CM1_SA (LM3S_I2CM1_BASE + LM3S_I2CM_SA_OFFSET) -#define LM3S_I2CM1_CS (LM3S_I2CM1_BASE + LM3S_I2CM_CS_OFFSET) -#define LM3S_I2CM1_DR (LM3S_I2CM1_BASE + LM3S_I2CM_DR_OFFSET) -#define LM3S_I2CM1_TPR (LM3S_I2CM1_BASE + LM3S_I2CM_TPR_OFFSET) -#define LM3S_I2CM1_IMR (LM3S_I2CM1_BASE + LM3S_I2CM_IMR_OFFSET) -#define LM3S_I2CM1_RIS (LM3S_I2CM1_BASE + LM3S_I2CM_RIS_OFFSET) -#define LM3S_I2CM1_MIS (LM3S_I2CM1_BASE + LM3S_I2CM_MIS_OFFSET) -#define LM3S_I2CM1_ICR (LM3S_I2CM1_BASE + LM3S_I2CM_ICR_OFFSET) -#define LM3S_I2CM1_CR (LM3S_I2CM1_BASE + LM3S_I2CM_CR_OFFSET) - -/* I2C1 Slave */ - -#define LM3S_I2CS1_OAR (LM3S_I2CS1_BASE + LM3S_I2CS_OAR_OFFSET) -#define LM3S_I2CS1_CSR (LM3S_I2CS1_BASE + LM3S_I2CS_CSR_OFFSET) -#define LM3S_I2CS1_DR (LM3S_I2CS1_BASE + LM3S_I2CS_DR_OFFSET) -#define LM3S_I2CS1_IMR (LM3S_I2CS1_BASE + LM3S_I2CS_IMR_OFFSET) -#define LM3S_I2CS1_RIS (LM3S_I2CS1_BASE + LM3S_I2CS_RIS_OFFSET) -#define LM3S_I2CS1_MIS (LM3S_I2CS1_BASE + LM3S_I2CS_MIS_OFFSET) -#define LM3S_I2CS1_ICR (LM3S_I2CS1_BASE + LM3S_I2CS_ICR_OFFSET) - -#endif -#endif - -/* I2C_Register Bit Definitions *****************************************************/ - -/* I2C Master Slave Address (I2CM_SA), offset 0x000 */ - -#define I2CM_SA_RS (1 << 0) /* Bit 0: Receive/Send */ -#define I2CM_SA_SA_SHIFT 1 /* Bits 7-1: I2C Slave Address */ -#define I2CM_SA_SA_MASK (0x7f << I2CM_SA_SA_SHIFT) - -/* I2C Master Control/Status (I2CM_CS), offset 0x004 */ - -#define I2CM_CS_BUSY (1 << 0) /* Bit 0: I2C Busy (read) */ -#define I2CM_CS_ERROR (1 << 1) /* Bit 1: Error in last bus operation (read) */ -#define I2CM_CS_ADRACK (1 << 2) /* Bit 2: Acknowledge Address (read) */ -#define I2CM_CS_DATACK (1 << 3) /* Bit 3: Acknowledge Data (read) */ -#define I2CM_CS_ARBLST (1 << 4) /* Bit 4: Arbitration Lost (read) */ -#define I2CM_CS_IDLE (1 << 5) /* Bit 5: I2C Idle (read) */ -#define I2CM_CS_BUSBSY (1 << 6) /* Bit 6: Bus Busy (read) */ - -#define I2CM_CS_RUN (1 << 0) /* Bit 0: I2C Master Enable (write) */ -#define I2CM_CS_START (1 << 1) /* Bit 1: Generate START (write) */ -#define I2CM_CS_STOP (1 << 2) /* Bit 2: Generate STOP (write) */ -#define I2CM_CS_ACK (1 << 3) /* Bit 3: Data Acknowledge Enable (write) */ - -/* I2C Master Data (I2CM_DR), offset 0x008 */ - -#define I2CM_DR_MASK 0xff /* Bits 7-0: Data transferred */ - -/* I2C Master Timer Period (I2CM_TPR), offset 0x00c */ - -#define I2CM_TPR_MASK 0xff /* Bits 7-0: SCL Clock Period */ - -/* I2C Master Interrupt Mask (I2CM_IMR), offset 0x010 */ - -#define I2CM_IMR_IM (1 << 0) /* Bit 0: Interrupt Mask */ - -/* I2C Master Raw Interrupt Status (I2CM_RIS), offset 0x014 */ - -#define I2CM_RIS_RIS (1 << 0) /* Bit 0: Raw Interrupt Status */ - -/* I2C Master Masked Interrupt Status (I2CM_MIS), offset 0x018 */ - -#define I2CM_MIS_MIS (1 << 0) /* Bit 0: Masked Interrupt Status */ - -/* I2C Master Masked Interrupt Status (I2CM_ICR), offset 0x01c */ - -#define I2CM_ICR_IC (1 << 0) /* Bit 0: Masked Interrupt Status */ - -/* I2C Master Configuration (I2CM_CR), offset 0x020 */ - -#define I2CM_CR_LPBK (1 << 0) /* Bit 0:: I2C Loopback */ -#define I2CM_CR_MFE (1 << 4 ) /* Bit 4: I2C Master Function Enable */ -#define I2CM_CR_SFE (1 << 5) /* Bit 5: I2C Slave Function Enable */ - -/* I2C Slave Own Address (I2CS_OAR), offset 0x000 */ - -#define I2CS_OAR_MASK 0xff /* Bits 7-0: I2C Slave Own Address */ - -/* I2C Slave Control/Status (I2CS_CSR), offset 0x004 */ - -#define I2CS_CSR_RREQ (1 << 0) /* Bit 0: Receive Request (read) */ -#define I2CS_CSR_TREQ (1 << 1) /* Bit 1: Transmit Request (read) */ -#define I2CS_CSR_FBR (1 << 2) /* Bit 2: First Byte Received (read) */ - -#define I2CS_CSR_DA (1 << 0) /* Bit 0: Device Active (write) */ - -/* I2C Slave Data (I2CS_DR), offset 0x008 */ - -#define I2CS_DR_MASK 0xff /* Bits 7-0: Data for Transfer */ - -/* I2C Slave Interrupt Mask (I2CS_IMR), offset 0x00c */ - -#define I2CM_IMR_DATAIM (1 << 0) /* Bit 0: Data Interrupt Mask */ - -/* I2C Slave Raw Interrupt Status (I2CS_RIS), offset 0x010 */ - -#define I2CM_RIS_DATARIS (1 << 0) /* Bit 0: Data Raw Interrupt Status */ - -/* I2C Slave Masked Interrupt Status (I2CS_MIS), offset 0x014 */ - -#define I2CM_MIS_DATAMIS (1 << 0) /* Bit 0: Data Masked Interrupt Status */ - -/* I2C Slave Interrupt Clear (I2CS_ICR), offset 0x018 */ - -#define I2CM_ICR_DATAIC (1 << 0) /* Bit 0: Data Interrupt Clear */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_I2C_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h b/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h deleted file mode 100644 index be0d8b58d..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h +++ /dev/null @@ -1,360 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_memorymap.h - * - * Copyright (C) 2009-2010 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_MEMORYMAP_H -#define __ARCH_ARM_SRC_LM3S_LM3S_MEMORYMAP_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* Memory map ***********************************************************************/ - -#if defined(CONFIG_ARCH_CHIP_LM3S6918) || defined(CONFIG_ARCH_CHIP_LM3S6432) || \ - defined(CONFIG_ARCH_CHIP_LM3S6965) || defined(CONFIG_ARCH_CHIP_LM3S8962) -# define LM3S_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */ - /* -0x1fffffff: Reserved */ -# define LM3S_SRAM_BASE 0x20000000 /* -0x2000ffff: Bit-banded on-chip SRAM */ - /* -0x21ffffff: Reserved */ -# define LM3S_ASRAM_BASE 0x22000000 /* -0x221fffff: Bit-band alias of 20000000- */ - /* -0x3fffffff: Reserved */ -# 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 */ -# define LM3S_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */ -# define LM3S_FPB_BASE 0xe0002000 /* -0xe0002fff: Flash Patch and Breakpoint */ - /* -0xe000dfff: Reserved */ -# define LM3S_NVIC_BASE 0xe000e000 /* -0xe000efff: Nested Vectored Interrupt Controller */ - /* -0xe003ffff: Reserved */ -# define LM3S_TPIU_BASE 0xe0040000 /* -0xe0040fff: Trace Port Interface Unit */ - /* -0xffffffff: Reserved */ -#elif defined(CONFIG_ARCH_CHIP_LM3S9B96) -# define LM3S_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */ - /* -0x1fffffff: Reserved */ -# define LM3S_SRAM_BASE 0x20000000 /* -0x2000ffff: Bit-banded on-chip SRAM */ - /* -0x21ffffff: Reserved */ -# define LM3S_ASRAM_BASE 0x22000000 /* -0x221fffff: Bit-band alias of 20000000- */ - /* -0x3fffffff: Reserved */ -# define LM3S_PERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */ - /* -0x41ffffff: Peripherals */ -# define LM3S_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alise of 40000000- */ - /* -0x5fffffff: Reserved */ -# define LM3S_EPI0RAM_BASE 0x60000000 /* -0xDfffffff: EPI0 mapped peripheral and RAM */ -# define LM3S_ITM_BASE 0xe0000000 /* -0xe0000fff: Instrumentation Trace Macrocell */ -# define LM3S_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */ -# define LM3S_FPB_BASE 0xe0002000 /* -0xe0002fff: Flash Patch and Breakpoint */ - /* -0xe000dfff: Reserved */ -# define LM3S_NVIC_BASE 0xe000e000 /* -0xe000efff: Nested Vectored Interrupt Controller */ - /* -0xe003ffff: Reserved */ -# define LM3S_TPIU_BASE 0xe0040000 /* -0xe0040fff: Trace Port Interface Unit */ - /* -0xffffffff: Reserved */ -#else -# error "Memory map not specified for this LM3S chip" -#endif - -/* Peripheral base addresses ********************************************************/ -/* The LM3S6918 and LM3S6965 differ by only the presence or absence of a few differnt - * peripheral modules. They could probably be combined into one peripheral memory - * map. However, keeping them separate does also provide so early, compile-time - * error detection that makes the duplication worthwhile. - */ - -#if defined(CONFIG_ARCH_CHIP_LM3S6918) -/* FiRM Peripheral Base Addresses */ - -# 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 + 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 */ -#elif defined(CONFIG_ARCH_CHIP_LM3S6432) -/* FiRM Peripheral Base Addresses */ - -# 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 */ - /* -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 + 0x20000) /* -0x207ff: I2C Master 0 */ -# define LM3S_I2CS0_BASE (LM3S_PERIPH_BASE + 0x20800) /* -0x20fff: I2C Slave 0 */ - /* -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 */ - /* -0x27fff: Reserved */ -# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ - /* -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 */ - /* -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 */ - -#elif defined(CONFIG_ARCH_CHIP_LM3S6965) -/* FiRM Peripheral Base Addresses */ - -# 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 */ - /* -0x0bfff: Reserved */ -# define LM3S_UART0_BASE (LM3S_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ -# define LM3S_UART1_BASE (LM3S_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ -# define LM3S_UART2_BASE (LM3S_PERIPH_BASE + 0x0e000) /* -0x0dfff: UART2 */ - /* -0x1ffff: Reserved */ -/* Peripheral Base Addresses */ - -# 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 */ - /* -0x27fff: Reserved */ -# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ - /* -0x2bfff: Reserved */ -# define LM3S_QEI0_BASE (LM3S_PERIPH_BASE + 0x2c000) /* -0x2cfff: QEI0 */ -# define LM3S_QEI1_BASE (LM3S_PERIPH_BASE + 0x2d000) /* -0x2dfff: QEI1 */ - /* -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 */ -#elif defined(CONFIG_ARCH_CHIP_LM3S8962) -/* FiRM Peripheral Base Addresses */ - -# 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 */ - /* -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 + 0x20000) /* -0x207ff: I2C Master 0 */ -# define LM3S_I2CS0_BASE (LM3S_PERIPH_BASE + 0x20800) /* -0x20fff: I2C Slave 0 */ - /* -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 */ - /* -0x27fff: Reserved */ -# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ - /* -0x2bfff: Reserved */ -# define LM3S_QEI0_BASE (LM3S_PERIPH_BASE + 0x2c000) /* -0x2cfff: QEI0 */ -# define LM3S_QEI1_BASE (LM3S_PERIPH_BASE + 0x2d000) /* -0x2dfff: QEI1 */ - /* -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 */ - /* -0x3fffff: Reserved */ -# define LM3S_CANCON_BASE (LM3S_PERIPH_BASE + 0x40000) /* -0x40fff: CAN Controller */ - /* -0x47fff: Reserved */ -# define LM3S_ETHCON_BASE (LM3S_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ - /* -0xfcfff: Reserved */ -# define LM3S_HIBERNATE_BASE (LM3S_PERIPH_BASE + 0xfc000) /* -0xfcfff: Hibernation 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 */ -#elif defined(CONFIG_ARCH_CHIP_LM3S9B96) -/* FiRM Peripheral Base Addresses */ - -# 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: SSI0 */ - /* -0x0bfff: Reserved */ -# define LM3S_UART0_BASE (LM3S_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */ -# define LM3S_UART1_BASE (LM3S_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */ -# define LM3S_UART2_BASE (LM3S_PERIPH_BASE + 0x0e000) /* -0x0dfff: UART2 */ - /* -0x1ffff: Reserved */ -/* Peripheral Base Addresses */ - -# 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 */ - -# define LM3S_PWM0_BASE (LM3S_PERIPH_BASE + 0x28000) /* -0x28fff: PWM */ - /* -0x2bfff: Reserved */ -# define LM3S_QEI0_BASE (LM3S_PERIPH_BASE + 0x2c000) /* -0x2cfff: QEI0 */ -# define LM3S_QEI1_BASE (LM3S_PERIPH_BASE + 0x2d000) /* -0x2dfff: QEI1 */ - /* -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_ADC0_BASE (LM3S_PERIPH_BASE + 0x38000) /* -0x38fff: ADC 0 */ -# define LM3S_ADC1_BASE (LM3S_PERIPH_BASE + 0x39000) /* -0x39fff: ADC 1 */ - /* -0x3bfff: Reserved */ -# define LM3S_COMPARE_BASE (LM3S_PERIPH_BASE + 0x3c000) /* -0x3cfff: Analog Comparators */ -# define LM3S_GPIOJ_BASE (LM3S_PERIPH_BASE + 0x3d000) /* -0x3dfff: GPIO Port J */ - /* -0x3ffff: Reserved */ -# define LM3S_CAN0_BASE (LM3S_PERIPH_BASE + 0x40000) /* -0x40fff: CAN 0 */ -# define LM3S_CAN1_BASE (LM3S_PERIPH_BASE + 0x41000) /* -0x41fff: CAN 1 */ - /* -0x47fff: Reserved */ -# define LM3S_ETHCON_BASE (LM3S_PERIPH_BASE + 0x48000) /* -0x48fff: Ethernet Controller */ - /* -0x49fff: Reserved */ -# define LM3S_USB_BASE (LM3S_PERIPH_BASE + 0x50000) /* -0x50fff: USB */ - /* -0x53fff: Reserved */ -# define LM3S_I2S0_BASE (LM3S_PERIPH_BASE + 0x54000) /* -0x54fff: I2S 0 */ - /* -0x57fff: Reserved */ -# define LM3S_GPIOAAHB_BASE (LM3S_PERIPH_BASE + 0x58000) /* -0x58fff: GPIO Port A (AHB aperture) */ -# define LM3S_GPIOBAHB_BASE (LM3S_PERIPH_BASE + 0x59000) /* -0x59fff: GPIO Port B (AHB aperture) */ -# define LM3S_GPIOCAHB_BASE (LM3S_PERIPH_BASE + 0x5A000) /* -0x5afff: GPIO Port C (AHB aperture) */ -# define LM3S_GPIODAHB_BASE (LM3S_PERIPH_BASE + 0x5B000) /* -0x5bfff: GPIO Port D (AHB aperture) */ -# define LM3S_GPIOEAHB_BASE (LM3S_PERIPH_BASE + 0x5C000) /* -0x5cfff: GPIO Port E (AHB aperture) */ -# define LM3S_GPIOFAHB_BASE (LM3S_PERIPH_BASE + 0x5D000) /* -0x5dfff: GPIO Port F (AHB aperture) */ -# define LM3S_GPIOGAHB_BASE (LM3S_PERIPH_BASE + 0x5E000) /* -0x5efff: GPIO Port G (AHB aperture) */ -# define LM3S_GPIOHAHB_BASE (LM3S_PERIPH_BASE + 0x5F000) /* -0x5ffff: GPIO Port H (AHB aperture) */ -# define LM3S_GPIOJAHB_BASE (LM3S_PERIPH_BASE + 0x60000) /* -0x60fff: GPIO Port J (AHB aperture) */ - /* -0xcffff: Reserved */ -# define LM3S_EPI0_BASE (LM3S_PERIPH_BASE + 0xD0000) /* -0xd0fff: EPI 0 */ - /* -0xfcfff: Reserved */ -# define LM3S_FLASHCON_BASE (LM3S_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */ -# define LM3S_SYSCON_BASE (LM3S_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */ -# define LM3S_UDMA_BASE (LM3S_PERIPH_BASE + 0xff000) /* -0xfffff: System Control */ - /* -0x1ffffff: Reserved */ -#else -# error "Peripheral base addresses not specified for this LM3S chip" -#endif - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ssi.h b/nuttx/arch/arm/src/lm3s/lm3s_ssi.h deleted file mode 100644 index 482dab326..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_ssi.h +++ /dev/null @@ -1,235 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_ssi.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_SSI_H -#define __ARCH_ARM_SRC_LM3S_LM3S_SSI_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include - -#if LM3S_NSSI > 0 - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* SSI register offsets *************************************************************/ - -#define LM3S_SSI_CR0_OFFSET 0x000 /* SSI Control 0 */ -#define LM3S_SSI_CR1_OFFSET 0x004 /* SSI Control 1 */ -#define LM3S_SSI_DR_OFFSET 0x008 /* SSI Data */ -#define LM3S_SSI_SR_OFFSET 0x00c /* SSI Status */ -#define LM3S_SSI_CPSR_OFFSET 0x010 /* SSI Clock Prescale */ -#define LM3S_SSI_IM_OFFSET 0x014 /* SSI Interrupt Mask */ -#define LM3S_SSI_RIS_OFFSET 0x018 /* SSI Raw Interrupt Status */ -#define LM3S_SSI_MIS_OFFSET 0x01c /* SSI Masked Interrupt Status */ -#define LM3S_SSI_ICR_OFFSET 0x020 /* SSI Interrupt Clear */ -#define LM3S_SSI_PERIPHID4_OFFSET 0xfd0 /* SSI Peripheral Identification 4 */ -#define LM3S_SSI_PERIPHID5_OFFSET 0xfd4 /* SSI Peripheral Identification 5 */ -#define LM3S_SSI_PERIPHID6_OFFSET 0xfd8 /* SSI Peripheral Identification 6 */ -#define LM3S_SSI_PERIPHID7_OFFSET 0xfdc /* SSI Peripheral Identification 7 */ -#define LM3S_SSI_PERIPHID0_OFFSET 0xfe0 /* SSI Peripheral Identification 0 */ -#define LM3S_SSI_PERIPHID1_OFFSET 0xfe4 /* SSI Peripheral Identification 1 */ -#define LM3S_SSI_PERIPHID2_OFFSET 0xfe8 /* SSI Peripheral Identification 2 */ -#define LM3S_SSI_PERIPHID3_OFFSET 0xfec /* SSI Peripheral Identification 3 */ -#define LM3S_SSI_PCELLID0_OFFSET 0xff0 /* SSI PrimeCell Identification 0 */ -#define LM3S_SSI_PCELLID1_OFFSET 0xff4 /* SSI PrimeCell Identification 1 */ -#define LM3S_SSI_PCELLID2_OFFSET 0xff8 /* SSI PrimeCell Identification 2 */ -#define LM3S_SSI_PCELLID3_OFFSET 0xffc /* SSI PrimeCell Identification 3 */ - -/* SSI register addresses ***********************************************************/ - -#define LM3S_SSI0_CR0 (LM3S_SSI0_BASE + LM3S_SSI_CR0_OFFSET) -#define LM3S_SSI0_CR1 (LM3S_SSI0_BASE + LM3S_SSI_CR1_OFFSET) -#define LM3S_SSI0_DR (LM3S_SSI0_BASE + LM3S_SSI_DR_OFFSET) -#define LM3S_SSI0_SR (LM3S_SSI0_BASE + LM3S_SSI_SR_OFFSET) -#define LM3S_SSI0_CPSR (LM3S_SSI0_BASE + LM3S_SSI_CPSR_OFFSET) -#define LM3S_SSI0_IM (LM3S_SSI0_BASE + LM3S_SSI_IM_OFFSET) -#define LM3S_SSI0_RIS (LM3S_SSI0_BASE + LM3S_SSI_RIS_OFFSET) -#define LM3S_SSI0_MIS (LM3S_SSI0_BASE + LM3S_SSI_MIS_OFFSET) -#define LM3S_SSI0_ICR (LM3S_SSI0_BASE + LM3S_SSI_ICR_OFFSET) -#define LM3S_SSI0_PERIPHID4 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID4_OFFSET) -#define LM3S_SSI0_PERIPHID5 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID5_OFFSET) -#define LM3S_SSI0_PERIPHID6 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID6_OFFSET) -#define LM3S_SSI0_PERIPHID7 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID7_OFFSET) -#define LM3S_SSI0_PERIPHID0 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID0_OFFSET) -#define LM3S_SSI0_PERIPHID1 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID1_OFFSET) -#define LM3S_SSI0_PERIPHID2 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID2_OFFSET) -#define LM3S_SSI0_PERIPHID3 (LM3S_SSI0_BASE + LM3S_SSI_PERIPHID3_OFFSET) -#define LM3S_SSI0_PCELLID0 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID0_OFFSET) -#define LM3S_SSI0_PCELLID1 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID1_OFFSET) -#define LM3S_SSI0_PCELLID2 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID2_OFFSET) -#define LM3S_SSI0_PCELLID3 (LM3S_SSI0_BASE + LM3S_SSI_PCELLID3_OFFSET) - -#if LM3S_NSSI > 1 -#define LM3S_SSI1_CR0 (LM3S_SSI1_BASE + LM3S_SSI_CR0_OFFSET) -#define LM3S_SSI1_CR1 (LM3S_SSI1_BASE + LM3S_SSI_CR1_OFFSET) -#define LM3S_SSI1_DR (LM3S_SSI1_BASE + LM3S_SSI_DR_OFFSET) -#define LM3S_SSI1_SR (LM3S_SSI1_BASE + LM3S_SSI_SR_OFFSET) -#define LM3S_SSI1_CPSR (LM3S_SSI1_BASE + LM3S_SSI_CPSR_OFFSET) -#define LM3S_SSI1_IM (LM3S_SSI1_BASE + LM3S_SSI_IM_OFFSET) -#define LM3S_SSI1_RIS (LM3S_SSI1_BASE + LM3S_SSI_RIS_OFFSET) -#define LM3S_SSI1_MIS (LM3S_SSI1_BASE + LM3S_SSI_MIS_OFFSET) -#define LM3S_SSI1_ICR (LM3S_SSI1_BASE + LM3S_SSI_ICR_OFFSET) -#define LM3S_SSI1_PERIPHID4 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID4_OFFSET) -#define LM3S_SSI1_PERIPHID5 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID5_OFFSET) -#define LM3S_SSI1_PERIPHID6 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID6_OFFSET) -#define LM3S_SSI1_PERIPHID7 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID7_OFFSET) -#define LM3S_SSI1_PERIPHID0 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID0_OFFSET) -#define LM3S_SSI1_PERIPHID1 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID1_OFFSET) -#define LM3S_SSI1_PERIPHID2 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID2_OFFSET) -#define LM3S_SSI1_PERIPHID3 (LM3S_SSI1_BASE + LM3S_SSI_PERIPHID3_OFFSET) -#define LM3S_SSI1_PCELLID0 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID0_OFFSET) -#define LM3S_SSI1_PCELLID1 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID1_OFFSET) -#define LM3S_SSI1_PCELLID2 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID2_OFFSET) -#define LM3S_SSI1_PCELLID3 (LM3S_SSI1_BASE + LM3S_SSI_PCELLID3_OFFSET) - -#define LM3S_SSI_BASE(n) (LM3S_SSI0_BASE + (n)*0x01000) - -#define LM3S_SSI_CR0(n) (LM3S_SSI_BASE(n) + LM3S_SSI_CR0_OFFSET) -#define LM3S_SSI_CR1(n) (LM3S_SSI_BASE(n) + LM3S_SSI_CR1_OFFSET) -#define LM3S_SSI_DR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_DR_OFFSET) -#define LM3S_SSI_SR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_SR_OFFSET) -#define LM3S_SSI_CPSR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_CPSR_OFFSET) -#define LM3S_SSI_IM(n) (LM3S_SSI_BASE(n) + LM3S_SSI_IM_OFFSET) -#define LM3S_SSI_RIS(n) (LM3S_SSI_BASE(n) + LM3S_SSI_RIS_OFFSET) -#define LM3S_SSI_MIS(n) (LM3S_SSI_BASE(n) + LM3S_SSI_MIS_OFFSET) -#define LM3S_SSI_ICR(n) (LM3S_SSI_BASE(n) + LM3S_SSI_ICR_OFFSET) -#define LM3S_SSI_PERIPHID4(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID4_OFFSET) -#define LM3S_SSI_PERIPHID5(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID5_OFFSET) -#define LM3S_SSI_PERIPHID6(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID6_OFFSET) -#define LM3S_SSI_PERIPHID7(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID7_OFFSET) -#define LM3S_SSI_PERIPHID0(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID0_OFFSET) -#define LM3S_SSI_PERIPHID1(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID1_OFFSET) -#define LM3S_SSI_PERIPHID2(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID2_OFFSET) -#define LM3S_SSI_PERIPHID3(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PERIPHID3_OFFSET) -#define LM3S_SSI_PCELLID0(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID0_OFFSET) -#define LM3S_SSI_PCELLID1(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID1_OFFSET) -#define LM3S_SSI_PCELLID2(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID2_OFFSET) -#define LM3S_SSI_PCELLID3(n) (LM3S_SSI_BASE(n) + LM3S_SSI_PCELLID3_OFFSET) -#endif /* LM3S_NSSI > 1 */ - -/* SSI register bit defitiions ******************************************************/ - -/* SSI Control 0 (SSICR0), offset 0x000 */ - -#define SSI_CR0_DSS_SHIFT 0 /* Bits 3-0: SSI Data Size Select */ -#define SSI_CR0_DSS_MASK (0x0f << SSI_CR0_DSS_SHIFT) -#define SSI_CR0_DSS(n) ((n-1) << SSI_CR0_DSS_SHIFT) /* n={4,5,..16} */ -#define SSI_CR0_FRF_SHIFT 4 /* Bits 5-4: SSI Frame Format Select */ -#define SSI_CR0_FRF_MASK (3 << SSI_CR0_FRF_SHIFT) -#define SSI_CR0_FRF_SPI (0 << SSI_CR0_FRF_SHIFT) /* Freescale SPI format */ -#define SSI_CR0_FRF_SSFF (1 << SSI_CR0_FRF_SHIFT) /* TI synchronous serial fram format */ -#define SSI_CR0_FRF_UWIRE (2 << SSI_CR0_FRF_SHIFT) /* MICROWIRE frame format */ -#define SSI_CR0_SPO (1 << 6) /* Bit 6: SSI Serial Clock Polarity */ -#define SSI_CR0_SPH (1 << 7) /* Bit 7: SSI Serial Clock Phase */ -#define SSI_CR0_SCR_SHIFT 8 /* Bits 15-8: SSI Serial Clock Rate */ -#define SSI_CR0_SCR_MASK (0xff << SSI_CR0_SCR_SHIFT) - -/* SSI Control 1 (SSICR1), offset 0x004 */ - -#define SSI_CR1_LBM (1 << 0) /* Bit 0: SSI Loopback Mode */ -#define SSI_CR1_SSE (1 << 1) /* Bit 1: SSI Synchronous Serial Port Enable */ -#define SSI_CR1_MS (1 << 2) /* Bit 2: SSI Master/Slave Select slave */ -#define SSI_CR1_SOD (1 << 3) /* Bit 3: SSI Slave Mode Output Disable */ - -/* SSI Data (SSIDR), offset 0x008 */ - -#define SSI_DR_MASK 0xffff /* Bits 15-0: SSI data */ - -/* SSI Status (SSISR), offset 0x00c */ - -#define SSI_SR_TFE (1 << 0) /* Bit 0: SSI Transmit FIFO Empty */ -#define SSI_SR_TNF (1 << 1) /* Bit 1: SSI Transmit FIFO Not Full */ -#define SSI_SR_RNE (1 << 2) /* Bit 2: SSI Receive FIFO Not Empty */ -#define SSI_SR_RFF (1 << 3) /* Bit 3: SSI Receive FIFO Full */ -#define SSI_SR_BSY (1 << 4) /* Bit 4: SSI Busy Bit */ - -/* SSI Clock Prescale (SSICPSR), offset 0x010 */ - -#define SSI_CPSR_DIV_MASK 0xff /* Bits 7-0: SSI Clock Prescale Divisor */ - -/* SSI Interrupt Mask (SSIIM), offset 0x014 */ - -#define SSI_IM_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Interrupt Mask */ -#define SSI_IM_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Interrupt Mask */ -#define SSI_IM_RX (1 << 2) /* Bit 2: SSI Receive FIFO Interrupt Mask */ -#define SSI_IM_TX (1 << 3) /* Bit 3: SSI Transmit FIFO Interrupt Mask */ - -/* SSI Raw Interrupt Status (SSIRIS), offset 0x018 */ - -#define SSI_RIS_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Raw Interrupt Status */ -#define SSI_RIS_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Raw Interrupt Status */ -#define SSI_RIS_RX (1 << 2) /* Bit 2: SSI Receive FIFO Raw Interrupt Status */ -#define SSI_RIS_TX (1 << 3) /* Bit 3: SSI Transmit FIFO Raw Interrupt Status */ - -/* SSI Masked Interrupt Status (SSIMIS), offset 0x01c */ - -#define SSI_MIS_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Masked Interrupt Status */ -#define SSI_MIS_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Masked Interrupt Status */ -#define SSI_MIS_RX (1 << 2) /* Bit 2: SSI Receive FIFO Masked Interrupt Status */ -#define SSI_MIS_TX (1 << 3) /* Bit 3: SSI Transmit FIFO Masked Interrupt Status */ - -/* SSI Interrupt Clear (SSIICR), offset 0x020 */ - -#define SSI_ICR_ROR (1 << 0) /* Bit 0: SSI Receive Overrun Interrupt Clear */ -#define SSI_ICR_RT (1 << 1) /* Bit 1: SSI Receive Time-Out Interrupt Clear */ - -/* SSI Peripheral Identification n (SSIPERIPHIDn), offset 0xfd0-0xfec */ - -#define SSI_PERIPHID_MASK 0xff /* Bits 7-0: SSI Peripheral ID n */ - -/* SSI PrimeCell Identification n (SSIPCELLIDn), offset 0xff0-0xffc */ - -#define SSI_PCELLID_MASK 0xff /* Bits 7-0: SSI Prime cell ID */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -#endif /* LM3S_NSSI > 0 */ -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_SSI_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h b/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h deleted file mode 100644 index c59b921c4..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h +++ /dev/null @@ -1,495 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_syscontrol.h - * - * Copyright (C) 2009-2010 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 - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* System Control Register Offsets **************************************************/ - -#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*/ - -/* 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_MINOR_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_GPIO(n) (1 << (n)) -#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) -# define SYSCON_LPDOPCTL_2500MV (0x00 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.5V (reset)*/ -# define SYSCON_LPDOPCTL_2450MV (0x01 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.45V */ -# define SYSCON_LPDOPCTL_2400MV (0x02 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.4V */ -# define SYSCON_LPDOPCTL_2350MV (0x03 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.35V */ -# define SYSCON_LPDOPCTL_2300MV (0x04 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.3V */ -# define SYSCON_LPDOPCTL_2250MV (0x05 << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.25V */ -# define SYSCON_LPDOPCTL_2750MV (0x1b << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.75V */ -# define SYSCON_LPDOPCTL_2700MV (0x1c << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.7V */ -# define SYSCON_LPDOPCTL_2650MV (0x1d << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.65V */ -# define SYSCON_LPDOPCTL_2600MV (0x1e << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.6V */ -# define SYSCON_LPDOPCTL_2550MV (0x1f << SYSCON_LDOPCTL_VADJ_SHIFT) /* 2.55V */ - -/* 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_GPIO(n) (1 << (n)) -#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_OSCSRC_MOSC (0 << SYSCON_RCC_OSCSRC_SHIFT) /* Main oscillator */ -# define SYSCON_RCC_OSCSRC_IOSC (1 << SYSCON_RCC_OSCSRC_SHIFT) /* Internal oscillator (reset) */ -# define SYSCON_RCC_OSCSRC_IOSC4 (2 << SYSCON_RCC_OSCSRC_SHIFT) /* Internal oscillator / 4 */ -# define SYSCON_RCC_OSCSRC_30KHZ (3 << SYSCON_RCC_OSCSRC_SHIFT) /* 30KHz internal oscillator */ -#define SYSCON_RCC_XTAL_SHIFT 6 /* Bits 10-6: Crystal Value */ -#define SYSCON_RCC_XTAL_MASK (0x1f << SYSCON_RCC_XTAL_SHIFT) -# define SYSCON_RCC_XTAL1000KHZ ( 0 << SYSCON_RCC_XTAL_SHIFT) /* 1.0000MHz (NO PLL) */ -# define SYSCON_RCC_XTAL1843KHZ ( 1 << SYSCON_RCC_XTAL_SHIFT) /* 1.8432MHz (NO PLL) */ -# define SYSCON_RCC_XTAL2000KHZ ( 2 << SYSCON_RCC_XTAL_SHIFT) /* 2.0000MHz (NO PLL) */ -# define SYSCON_RCC_XTAL2580KHZ ( 3 << SYSCON_RCC_XTAL_SHIFT) /* 2.4576MHz (NO PLL) */ -# define SYSCON_RCC_XTAL3580KHZ ( 4 << SYSCON_RCC_XTAL_SHIFT) /* 3.5795MHz */ -# define SYSCON_RCC_XTAL3686KHZ ( 5 << SYSCON_RCC_XTAL_SHIFT) /* 3.6864MHz */ -# define SYSCON_RCC_XTAL4000KHZ ( 6 << SYSCON_RCC_XTAL_SHIFT) /* 4.0000MHz */ -# define SYSCON_RCC_XTAL4096KHZ ( 7 << SYSCON_RCC_XTAL_SHIFT) /* 4.0960MHz */ -# define SYSCON_RCC_XTAL4915KHZ ( 8 << SYSCON_RCC_XTAL_SHIFT) /* 4.9152MHz */ -# define SYSCON_RCC_XTAL5000KHZ ( 9 << SYSCON_RCC_XTAL_SHIFT) /* 5.0000MHz */ -# define SYSCON_RCC_XTAL5120KHZ (10 << SYSCON_RCC_XTAL_SHIFT) /* 5.1200MHz */ -# define SYSCON_RCC_XTAL6000KHZ (11 << SYSCON_RCC_XTAL_SHIFT) /* 6.0000MHz (reset value) */ -# define SYSCON_RCC_XTAL6144KHZ (12 << SYSCON_RCC_XTAL_SHIFT) /* 6.1440MHz */ -# define SYSCON_RCC_XTAL7373KHZ (13 << SYSCON_RCC_XTAL_SHIFT) /* 7.3728MHz */ -# define SYSCON_RCC_XTAL8000KHZ (14 << SYSCON_RCC_XTAL_SHIFT) /* 8.0000MHz */ -# define SYSCON_RCC_XTAL8192KHZ (15 << SYSCON_RCC_XTAL_SHIFT) /* 8.1920MHz */ -#ifdef CONFIG_ARCH_CHIP_LM3S9B96 -# define SYSCON_RCC_XTAL10000KHZ (16 << SYSCON_RCC_XTAL_SHIFT) /* 10.0 MHz (USB) */ -# define SYSCON_RCC_XTAL12000KHZ (17 << SYSCON_RCC_XTAL_SHIFT) /* 12.0 MHz (USB) */ -# define SYSCON_RCC_XTAL12888KHZ (18 << SYSCON_RCC_XTAL_SHIFT) /* 12.288 MHz */ -# define SYSCON_RCC_XTAL13560KHZ (19 << SYSCON_RCC_XTAL_SHIFT) /* 13.56 MHz */ -# define SYSCON_RCC_XTAL14318KHZ (20 << SYSCON_RCC_XTAL_SHIFT) /* 14.31818 MHz */ -# define SYSCON_RCC_XTAL16000KHZ (21 << SYSCON_RCC_XTAL_SHIFT) /* 16.0 MHz (USB) */ -# define SYSCON_RCC_XTAL16384KHZ (22 << SYSCON_RCC_XTAL_SHIFT) /* 16.384 MHz */ -#endif -#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 23 /* Bits 26-23: System Clock Divisor */ -#define SYSCON_RCC_SYSDIV_MASK (0x0f << SYSCON_RCC_SYSDIV_SHIFT) -# define SYSCON_RCC_SYSDIV(n) (((n)-1) << 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_OSCSRC2_MOSC (0 << SYSCON_RCC2_OSCSRC2_SHIFT) /* Main oscillator */ -# define SYSCON_RCC2_OSCSRC2_IOSC (1 << SYSCON_RCC2_OSCSRC2_SHIFT) /* Internal oscillator (reset) */ -# define SYSCON_RCC2_OSCSRC2_IOSC4 (2 << SYSCON_RCC2_OSCSRC2_SHIFT) /* Internal oscillator / 4 */ -# define SYSCON_RCC2_OSCSRC2_30KHZ (3 << SYSCON_RCC2_OSCSRC2_SHIFT) /* 30KHz internal oscillator */ -# define SYSCON_RCC2_OSCSRC2_32KHZ (7 << SYSCON_RCC2_OSCSRC2_SHIFT) /* 32.768KHz external oscillator */ -#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_SYSDIV(n) ((n-1) << 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_GPIO(n) (1 << (n)) -#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_GPIO(n) (1 << (n)) -#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_GPIO(n) (1 << (n)) -#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 */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_timer.h b/nuttx/arch/arm/src/lm3s/lm3s_timer.h deleted file mode 100644 index 7c4166293..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_timer.h +++ /dev/null @@ -1,125 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_timer.h - * - * Copyright (C) 2012 Max Nekludov. All rights reserved. - * Author: Max Nekludov - * - * 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_TIMER_H -#define __ARCH_ARM_SRC_LM3S_LM3S_TIMER_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* Timer register offsets ***********************************************************/ - -#define TIMER_GPTMCFG_OFFSET 0x000 -#define TIMER_GPTMTAMR_OFFSET 0x004 -#define TIMER_GPTMCTL_OFFSET 0x00C -#define TIMER_GPTMIMR_OFFSET 0x018 -#define TIMER_GPTMRIS_OFFSET 0x01C -#define TIMER_GPTMICR_OFFSET 0x024 -#define TIMER_GPTMTAILR_OFFSET 0x028 -#define TIMER_GPTMTAR_OFFSET 0x048 - -/* SSI register addresses ***********************************************************/ - -#define LM3S_TIMER_BASE(n) (LM3S_TIMER0_BASE + (n)*0x01000) - -#define LM3S_TIMER_GPTMCFG(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMCFG_OFFSET) -#define LM3S_TIMER_GPTMTAMR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMTAMR_OFFSET) -#define LM3S_TIMER_GPTMCTL(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMCTL_OFFSET) -#define LM3S_TIMER_GPTMIMR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMIMR_OFFSET) -#define LM3S_TIMER_GPTMRIS(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMRIS_OFFSET) -#define LM3S_TIMER_GPTMICR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMICR_OFFSET) -#define LM3S_TIMER_GPTMTAILR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMTAILR_OFFSET) -#define LM3S_TIMER_GPTMTAR(n) (LM3S_TIMER_BASE(n) + TIMER_GPTMTAR_OFFSET) - -/* SSI register bit defitiions ******************************************************/ - -/* GPTM Configuration (GPTMCFG), offset 0x000 */ - -#define TIMER_GPTMCFG_CFG_SHIFT 0 /* Bits 2-0: GPTM Configuration */ -#define TIMER_GPTM_CFG_MASK (0x07 << TIMER_GPTMCFG_CFG_SHIFT) -#define TIMER_GPTMCFG_CFG_32 (0 << TIMER_GPTMCFG_CFG_SHIFT) /* 32-bit timer configuration */ -#define TIMER_GPTMCFG_CFG_RTC (1 << TIMER_GPTMCFG_CFG_SHIFT) /* 32-bit real-time clock (RTC) counter configuration */ -#define TIMER_GPTMCFG_CFG_16 (1 << TIMER_GPTMCFG_CFG_SHIFT) /* 16-bit timer configuration */ - -/* GPTM Timer A Mode (GPTMTAMR), offset 0x004 */ - -#define TIMER_GPTMTAMR_TAMR_SHIFT 0 /* Bits 1-0: GPTM Timer A Mode */ -#define TIMER_GPTMTAMR_TAMR_MASK (0x03 << TIMER_GPTMTAMR_TAMR_SHIFT) -#define TIMER_GPTMTAMR_TAMR_ONESHOT (1 << TIMER_GPTMTAMR_TAMR_SHIFT) /* One-Shot Timer mode */ -#define TIMER_GPTMTAMR_TAMR_PERIODIC (2 << TIMER_GPTMTAMR_TAMR_SHIFT) /* Periodic Timer mode */ -#define TIMER_GPTMTAMR_TAMR_CAPTURE (3 << TIMER_GPTMTAMR_TAMR_SHIFT) /* Capture mode */ -#define TIMER_GPTMTAMR_TACMR_SHIFT 2 /* Bits 2: GPTM Timer A Capture Mode */ -#define TIMER_GPTMTAMR_TACMR_MASK (0x01 << TIMER_GPTMTAMR_TACMR_SHIFT) -#define TIMER_GPTMTAMR_TACMR_EDGECOUNT (0 << TIMER_GPTMTAMR_TACMR_SHIFT) /* Edge-Count mode */ -#define TIMER_GPTMTAMR_TACMR_EDGETIME (1 << TIMER_GPTMTAMR_TACMR_SHIFT) /* Edge-Time mode */ -#define TIMER_GPTMTAMR_TAAMS_SHIFT 3 /* Bits 3: GPTM Timer A Alternate Mode Select */ -#define TIMER_GPTMTAMR_TAAMS_MASK (0x01 << TIMER_GPTMTAMR_TAAMS_SHIFT) -#define TIMER_GPTMTAMR_TAAMS_CAPTURE (0 << TIMER_GPTMTAMR_TAAMS_SHIFT) /* Capture mode is enabled */ -#define TIMER_GPTMTAMR_TAAMS_PWM (1 << TIMER_GPTMTAMR_TAAMS_SHIFT) /* PWM mode is enabled */ -#define TIMER_GPTMTAMR_TACDIR_SHIFT 4 /* Bits 4: GPTM Timer A Count Direction */ -#define TIMER_GPTMTAMR_TACDIR_MASK (0x01 << TIMER_GPTMTAMR_TACDIR_SHIFT) -#define TIMER_GPTMTAMR_TACDIR_DOWN (0 << TIMER_GPTMTAMR_TACDIR_SHIFT) /* The timer counts down */ -#define TIMER_GPTMTAMR_TACDIR_UP (1 << TIMER_GPTMTAMR_TACDIR_SHIFT) /* When in one-shot or periodic mode, the timer counts up */ -#define TIMER_GPTMTAMR_TAMIE_SHIFT 5 /* Bits 5: GPTM Timer A Match Interrupt Enable */ -#define TIMER_GPTMTAMR_TAMIE_MASK (0x01 << TIMER_GPTMTAMR_TAMIE_SHIFT) - -/* GPTM Control (GPTMCTL), offset 0x00C */ - -#define TIMER_GPTMCTL_TAEN_SHIFT 0 /* Bits 0: GPTM Timer A Enable */ -#define TIMER_GPTMCTL_TAEN_MASK (0x01 << TIMER_GPTMCTL_TAEN_SHIFT) -#define TIMER_GPTMCTL_TASTALL_SHIFT 1 /* Bits 1: GPTM Timer A Stall Enable */ -#define TIMER_GPTMCTL_TASTALL_MASK (0x01 << TIMER_GPTMCTL_TASTALL_SHIFT) - -/* GPTM Interrupt Mask (GPTMIMR), offset 0x018 */ - -#define TIMER_GPTMIMR_TATOIM_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Interrupt Mask */ -#define TIMER_GPTMIMR_TATOIM_MASK (0x01 << TIMER_GPTMIMR_TATOIM_SHIFT) - -/* GPTM Raw Interrupt Status (GPTMRIS), offset 0x01C */ - -#define TIMER_GPTMRIS_TATORIS_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Raw Interrupt */ -#define TIMER_GPTMRIS_TATORIS_MASK (0x01 << TIMER_GPTMRIS_TATORIS_SHIFT) - -/* GPTM Interrupt Clear (GPTMICR), offset 0x024 */ - -#define TIMER_GPTMICR_TATOCINT_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Raw Interrupt Clear*/ -#define TIMER_GPTMICR_TATOCINT_MASK (0x01 << TIMER_GPTMICR_TATOCINT_SHIFT) - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_TIMER_H */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_uart.h b/nuttx/arch/arm/src/lm3s/lm3s_uart.h deleted file mode 100644 index 91bfb2266..000000000 --- a/nuttx/arch/arm/src/lm3s/lm3s_uart.h +++ /dev/null @@ -1,347 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lm3s/lm3s_uart.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_UART_H -#define __ARCH_ARM_SRC_LM3S_LM3S_UART_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* UART register offsets ************************************************************/ - -#define LM3S_UART_DR_OFFSET 0x000 /* UART Data */ -#define LM3S_UART_RSR_OFFSET 0x004 /* UART Receive Status */ -#define LM3S_UART_ECR_OFFSET 0x004 /* UART Error Clear */ -#define LM3S_UART_FR_OFFSET 0x018 /* UART Flag */ -#define LM3S_UART_ILPR_OFFSET 0x020 /* UART IrDA Low-Power Register */ -#define LM3S_UART_IBRD_OFFSET 0x024 /* UART Integer Baud-Rate Divisor*/ -#define LM3S_UART_FBRD_OFFSET 0x028 /* UART Fractional Baud-Rate Divisor */ -#define LM3S_UART_LCRH_OFFSET 0x02c /* UART Line Control */ -#define LM3S_UART_CTL_OFFSET 0x030 /* UART Control */ -#define LM3S_UART_IFLS_OFFSET 0x034 /* UART Interrupt FIFO Level Select */ -#define LM3S_UART_IM_OFFSET 0x038 /* UART Interrupt Mask */ -#define LM3S_UART_RIS_OFFSET 0x03c /* UART Raw Interrupt Status */ -#define LM3S_UART_MIS_OFFSET 0x040 /* UART Masked Interrupt Status */ -#define LM3S_UART_ICR_OFFSET 0x044 /* UART Interrupt Clear */ -#define LM3S_UART_PERIPHID4_OFFSET 0xfd0 /* UART Peripheral Identification 4 */ -#define LM3S_UART_PERIPHID5_OFFSET 0xfd4 /* UART Peripheral Identification 5 */ -#define LM3S_UART_PERIPHID6_OFFSET 0xfd8 /* UART Peripheral Identification 6 */ -#define LM3S_UART_PERIPHID7_OFFSET 0xfdc /* UART Peripheral Identification 7 */ -#define LM3S_UART_PERIPHID0_OFFSET 0xfe0 /* UART Peripheral Identification 0 */ -#define LM3S_UART_PERIPHID1_OFFSET 0xfe4 /* UART Peripheral Identification 1 */ -#define LM3S_UART_PERIPHID2_OFFSET 0xfe8 /* UART Peripheral Identification 2 */ -#define LM3S_UART_PERIPHID3_OFFSET 0xfec /* UART Peripheral Identification 3 */ -#define LM3S_UART_PCELLID0_OFFSET 0xff0 /* UART PrimeCell Identification 0 */ -#define LM3S_UART_PCELLID1_OFFSET 0xff4 /* UART PrimeCell Identification 1 */ -#define LM3S_UART_PCELLID2_OFFSET 0xff8 /* UART PrimeCell Identification 2 */ -#define LM3S_UART_PCELLID3_OFFSET 0xffc /* UART PrimeCell Identification 3 */ - -/* UART register addresses **********************************************************/ - -#define LM3S_UART_BASE(n) (LM3S_UART0_BASE + (n)*0x01000) - -#define LM3S_UART_DR(n) (LM3S_UART_BASE(n) + LM3S_UART_DR_OFFSET) -#define LM3S_UART_RSR(n) (LM3S_UART_BASE(n) + LM3S_UART_RSR_OFFSET) -#define LM3S_UART_ECR(n) (LM3S_UART_BASE(n) + LM3S_UART_ECR_OFFSET) -#define LM3S_UART_FR(n) (LM3S_UART_BASE(n) + LM3S_UART_FR_OFFSET) -#define LM3S_UART_ILPR(n) (LM3S_UART_BASE(n) + LM3S_UART_ILPR_OFFSET) -#define LM3S_UART_IBRD(n) (LM3S_UART_BASE(n) + LM3S_UART_IBRD_OFFSET) -#define LM3S_UART_FBRD(n) (LM3S_UART_BASE(n) + LM3S_UART_FBRD_OFFSET) -#define LM3S_UART_LCRH(n) (LM3S_UART_BASE(n) + LM3S_UART_LCRH_OFFSET) -#define LM3S_UART_CTL(n) (LM3S_UART_BASE(n) + LM3S_UART_CTL_OFFSET) -#define LM3S_UART_IFLS(n) (LM3S_UART_BASE(n) + LM3S_UART_IFLS_OFFSET) -#define LM3S_UART_IM(n) (LM3S_UART_BASE(n) + LM3S_UART_IM_OFFSET) -#define LM3S_UART_RIS(n) (LM3S_UART_BASE(n) + LM3S_UART_RIS_OFFSET) -#define LM3S_UART_MIS(n) (LM3S_UART_BASE(n) + LM3S_UART_MIS_OFFSET) -#define LM3S_UART_ICR(n) (LM3S_UART_BASE(n) + LM3S_UART_ICR_OFFSET) -#define LM3S_UART_PERIPHID4(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID4_OFFSET) -#define LM3S_UART_PERIPHID5(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID5_OFFSET) -#define LM3S_UART_PERIPHID6(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID6_OFFSET) -#define LM3S_UART_PERIPHID7(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID7_OFFSET) -#define LM3S_UART_PERIPHID0(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID0_OFFSET) -#define LM3S_UART_PERIPHID1(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID1_OFFSET) -#define LM3S_UART_PERIPHID2(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID2_OFFSET) -#define LM3S_UART_PERIPHID3(n) (LM3S_UART_BASE(n) + LM3S_UART_PERIPHID3_OFFSET) -#define LM3S_UART_PCELLID0(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID0_OFFSET) -#define LM3S_UART_PCELLID1(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID1_OFFSET) -#define LM3S_UART_PCELLID2(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID2_OFFSET) -#define LM3S_UART_PCELLID3(n) (LM3S_UART_BASE(n) + LM3S_UART_PCELLID3_OFFSET) - -#define LM3S_UART0_DR (LM3S_UART0_BASE + LM3S_UART_TDR_OFFSET) -#define LM3S_UART0_RSR (LM3S_UART0_BASE + LM3S_UART_RSR_OFFSET) -#define LM3S_UART0_ECR (LM3S_UART0_BASE + LM3S_UART_ECR_OFFSET) -#define LM3S_UART0_FR (LM3S_UART0_BASE + LM3S_UART_FR_OFFSET) -#define LM3S_UART0_ILPR (LM3S_UART0_BASE + LM3S_UART_ILPR_OFFSET) -#define LM3S_UART0_IBRD (LM3S_UART0_BASE + LM3S_UART_IBRD_OFFSET) -#define LM3S_UART0_FBRD (LM3S_UART0_BASE + LM3S_UART_FBRD_OFFSET) -#define LM3S_UART0_LCRH (LM3S_UART0_BASE + LM3S_UART_LCRH_OFFSET) -#define LM3S_UART0_CTL (LM3S_UART0_BASE + LM3S_UART_CTL_OFFSET) -#define LM3S_UART0_IFLS (LM3S_UART0_BASE + LM3S_UART_IFLS_OFFSET) -#define LM3S_UART0_IM (LM3S_UART0_BASE + LM3S_UART_IM_OFFSET) -#define LM3S_UART0_RIS (LM3S_UART0_BASE + LM3S_UART_RIS_OFFSET) -#define LM3S_UART0_MIS (LM3S_UART0_BASE + LM3S_UART_MIS_OFFSET) -#define LM3S_UART0_ICR (LM3S_UART0_BASE + LM3S_UART_ICR_OFFSET) -#define LM3S_UART0_PERIPHID4 (LM3S_UART0_BASE + LM3S_UART_PERIPHID4_OFFSET) -#define LM3S_UART0_PERIPHID5 (LM3S_UART0_BASE + LM3S_UART_PERIPHID5_OFFSET) -#define LM3S_UART0_PERIPHID6 (LM3S_UART0_BASE + LM3S_UART_PERIPHID6_OFFSET) -#define LM3S_UART0_PERIPHID7 (LM3S_UART0_BASE + LM3S_UART_PERIPHID7_OFFSET) -#define LM3S_UART0_PERIPHID0 (LM3S_UART0_BASE + LM3S_UART_PERIPHID0_OFFSET) -#define LM3S_UART0_PERIPHID1 (LM3S_UART0_BASE + LM3S_UART_PERIPHID1_OFFSET) -#define LM3S_UART0_PERIPHID2 (LM3S_UART0_BASE + LM3S_UART_PERIPHID2_OFFSET) -#define LM3S_UART0_PERIPHID3 (LM3S_UART0_BASE + LM3S_UART_PERIPHID3_OFFSET) -#define LM3S_UART0_PCELLID0 (LM3S_UART0_BASE + LM3S_UART_PCELLID0_OFFSET) -#define LM3S_UART0_PCELLID1 (LM3S_UART0_BASE + LM3S_UART_PCELLID1_OFFSET) -#define LM3S_UART0_PCELLID2 (LM3S_UART0_BASE + LM3S_UART_PCELLID2_OFFSET) -#define LM3S_UART0_PCELLID3 (LM3S_UART0_BASE + LM3S_UART_PCELLID3_OFFSET) - -#define LM3S_UART1_DR (LM3S_UART1_BASE + LM3S_UART_DR_OFFSET) -#define LM3S_UART1_RSR (LM3S_UART1_BASE + LM3S_UART_RSR_OFFSET) -#define LM3S_UART1_ECR (LM3S_UART1_BASE + LM3S_UART_ECR_OFFSET) -#define LM3S_UART1_FR (LM3S_UART1_BASE + LM3S_UART_FR_OFFSET) -#define LM3S_UART1_ILPR (LM3S_UART1_BASE + LM3S_UART_ILPR_OFFSET) -#define LM3S_UART1_IBRD (LM3S_UART1_BASE + LM3S_UART_IBRD_OFFSET) -#define LM3S_UART1_FBRD (LM3S_UART1_BASE + LM3S_UART_FBRD_OFFSET) -#define LM3S_UART1_LCRH (LM3S_UART1_BASE + LM3S_UART_LCRH_OFFSET) -#define LM3S_UART1_CTL (LM3S_UART1_BASE + LM3S_UART_CTL_OFFSET) -#define LM3S_UART1_IFLS (LM3S_UART1_BASE + LM3S_UART_IFLS_OFFSET) -#define LM3S_UART1_IM (LM3S_UART1_BASE + LM3S_UART_IM_OFFSET) -#define LM3S_UART1_RIS (LM3S_UART1_BASE + LM3S_UART_RIS_OFFSET) -#define LM3S_UART1_MIS (LM3S_UART1_BASE + LM3S_UART_MIS_OFFSET) -#define LM3S_UART1_ICR (LM3S_UART1_BASE + LM3S_UART_ICR_OFFSET) -#define LM3S_UART1_PERIPHID4 (LM3S_UART1_BASE + LM3S_UART_PERIPHID4_OFFSET) -#define LM3S_UART1_PERIPHID5 (LM3S_UART1_BASE + LM3S_UART_PERIPHID5_OFFSET) -#define LM3S_UART1_PERIPHID6 (LM3S_UART1_BASE + LM3S_UART_PERIPHID6_OFFSET) -#define LM3S_UART1_PERIPHID7 (LM3S_UART1_BASE + LM3S_UART_PERIPHID7_OFFSET) -#define LM3S_UART1_PERIPHID0 (LM3S_UART1_BASE + LM3S_UART_PERIPHID0_OFFSET) -#define LM3S_UART1_PERIPHID1 (LM3S_UART1_BASE + LM3S_UART_PERIPHID1_OFFSET) -#define LM3S_UART1_PERIPHID2 (LM3S_UART1_BASE + LM3S_UART_PERIPHID2_OFFSET) -#define LM3S_UART1_PERIPHID3 (LM3S_UART1_BASE + LM3S_UART_PERIPHID3_OFFSET) -#define LM3S_UART1_PCELLID0 (LM3S_UART1_BASE + LM3S_UART_PCELLID0_OFFSET) -#define LM3S_UART1_PCELLID1 (LM3S_UART1_BASE + LM3S_UART_PCELLID1_OFFSET) -#define LM3S_UART1_PCELLID2 (LM3S_UART1_BASE + LM3S_UART_PCELLID2_OFFSET) -#define LM3S_UART1_PCELLID3 (LM3S_UART1_BASE + LM3S_UART_PCELLID3_OFFSET) - -/* UART register bit settings *******************************************************/ - -/* UART Data (DR), offset 0x000 */ - -#define UART_DR_DATA_SHIFT 0 /* Bits 7-0: Data Transmitted or Received */ -#define UART_DR_DATA_MASK (0xff << UART_DR_DATA_SHIFT) -#define UART_DR_FE (1 << 8) /* Bit 8: UART Framing Error */ -#define UART_DR_PE (1 << 9) /* Bit 9: UART Parity Error */ -#define UART_DR_BE (1 << 10) /* Bit 10: UART Break Error */ -#define UART_DR_OE (1 << 11) /* Bit 11: UART Overrun Error */ - -/* UART Receive Status (RSR), offset 0x004 */ - -#define UART_RSR_FE (1 << 0) /* Bit 0: UART Framing Error */ -#define UART_RSR_PE (1 << 1) /* Bit 1: UART Parity Error */ -#define UART_RSR_BE (1 << 2) /* Bit 2: UART Break Error */ -#define UART_RSR_OE (1 << 3) /* Bit 3: UART Overrun Error */ - -/* UART Error Clear (ECR), offset 0x004 */ -/* Writing any value to this register clears pending error indications */ - -/* UART Flag (FR), offset 0x018 */ - -#define UART_FR_BUSY (1 << 3) /* Bit 3: UART Busy */ -#define UART_FR_RXFE (1 << 4) /* Bit 4: UART Receive FIFO Empty */ -#define UART_FR_TXFF (1 << 5) /* Bit 5: UART Transmit FIFO Full */ -#define UART_FR_RXFF (1 << 6) /* Bit 6: UART Receive FIFO Full */ -#define UART_FR_TXFE (1 << 7) /* Bit 7: UART Transmit FIFO Empty */ - -/* UART IrDA Low-Power Register (ILPR), offset 0x020 */ - -#define UART_ILPR_DVSR_MASK (0xff) /* Bits 7-0: IrDA Low-Power Divisor */ - -/* UART Integer Baud-Rate Divisor (IBRD), offset 0x024 */ - -#define UART_IBRD_DIVINT_MASK (0xffff) /* Bits 15-0: Integer Baud-Rate Divisor */ - -/* UART Fractional Baud-Rate Divisor (UARTFBRD), offset 0x028 */ - -#define UART_FBRD_DIVFRAC_MASK (0x3f) /* Bits 5-0: Fractional Baud-Rate Divisor */ - -/* Register 7: UART Line Control (LCRH), offset 0x02C */ - -#define UART_LCRH_BRK (1 << 0) /* Bit 0: UART Send Break */ -#define UART_LCRH_PEN (1 << 1) /* Bit 1: UART Parity Enable */ -#define UART_LCRH_EPS (1 << 2) /* Bit 2: UART Even Parity Select */ -#define UART_LCRH_STP2 (1 << 3) /* Bit 3: UART Two Stop Bits Select */ -#define UART_LCRH_FEN (1 << 4) /* Bit 4: UART Enable FIFOs */ -#define UART_LCRH_WLEN_SHIFT 5 /* Bits 6-5: UART Word Length */ -#define UART_LCRH_WLEN_MASK (3 << UART_LCRH_WLEN_SHIFT) -# define UART_LCRH_WLEN_5BITS (0 << UART_LCRH_WLEN_SHIFT) /* 5-bits (reset) */ -# define UART_LCRH_WLEN_6BITS (1 << UART_LCRH_WLEN_SHIFT) /* 6-bits */ -# define UART_LCRH_WLEN_7BITS (2 << UART_LCRH_WLEN_SHIFT) /* 7-bits */ -# define UART_LCRH_WLEN_8BITS (3 << UART_LCRH_WLEN_SHIFT) /* 8-bits */ -#define UART_LCRH_SPS (1 << 7) /* Bit 7: UART Stick Parity Select */ - -/* UART Control (CTL), offset 0x030 */ - -#define UART_CTL_UARTEN (1 << 0) /* Bit 0: UART Enable */ -#define UART_CTL_SIREN (1 << 1) /* Bit 1: UART SIR Enable */ -#define UART_CTL_SIRLP (1 << 2) /* Bit 2: UART SIR Low Power Mode */ -#define UART_CTL_LBE (1 << 7) /* Bit 7: UART Loop Back Enable */ -#define UART_CTL_TXE (1 << 8) /* Bit 8: UART Transmit Enable */ -#define UART_CTL_RXE (1 << 9) /* Bit 9: UART Receive Enable */ - -/* UART Interrupt FIFO Level Select (IFLS), offset 0x034 */ - -#define UART_IFLS_TXIFLSEL_SHIFT 0 /* Bits 2-0: UART Transmit Interrupt FIFO Level Select */ -#define UART_IFLS_TXIFLSEL_MASK (7 << UART_IFLS_TXIFLSEL_SHIFT) -# define UART_IFLS_TXIFLSEL_18th (0 << UART_IFLS_TXIFLSEL_SHIFT) /* 1/8th full */ -# define UART_IFLS_TXIFLSEL_14th (1 << UART_IFLS_TXIFLSEL_SHIFT) /* 1/4th full */ -# define UART_IFLS_TXIFLSEL_half (2 << UART_IFLS_TXIFLSEL_SHIFT) /* half full */ -# define UART_IFLS_TXIFLSEL_34th (3 << UART_IFLS_TXIFLSEL_SHIFT) /* 3/4th full */ -# define UART_IFLS_TXIFLSEL_78th (4 << UART_IFLS_TXIFLSEL_SHIFT) /* 7/8th full */ -#define UART_IFLS_RXIFLSEL_SHIFT 3 /* Bits 5-3: UART Receive Interrupt FIFO Level Select */ -#define UART_IFLS_RXIFLSEL_MASK (7 << UART_IFLS_RXIFLSEL_SHIFT) -# define UART_IFLS_RXIFLSEL_18th (0 << UART_IFLS_RXIFLSEL_SHIFT) /* 1/8th full */ -# define UART_IFLS_RXIFLSEL_14th (1 << UART_IFLS_RXIFLSEL_SHIFT) /* 1/4th full */ -# define UART_IFLS_RXIFLSEL_half (2 << UART_IFLS_RXIFLSEL_SHIFT) /* half full */ -# define UART_IFLS_RXIFLSEL_34th (3 << UART_IFLS_RXIFLSEL_SHIFT) /* 3/4th full */ -# define UART_IFLS_RXIFLSEL_78th (4 << UART_IFLS_RXIFLSEL_SHIFT) /* 7/8th full */ - -/* UART Interrupt Mask (IM), offset 0x038 */ - -#define UART_IM_RXIM (1 << 4) /* Bit 4: UART Receive Interrupt Mask */ -#define UART_IM_TXIM (1 << 5) /* Bit 5: UART Transmit Interrupt Mask */ -#define UART_IM_RTIM (1 << 6) /* Bit 6: UART Receive Time-Out Interrupt Mask */ -#define UART_IM_FEIM (1 << 7) /* Bit 7: UART Framing Error Interrupt Mask */ -#define UART_IM_PEIM (1 << 8) /* Bit 8: UART Parity Error Interrupt Mask */ -#define UART_IM_BEIM (1 << 9) /* Bit 9: UART Break Error Interrupt Mask */ -#define UART_IM_OEIM (1 << 10) /* Bit 10: UART Overrun Error Interrupt Mask */ - - -/* UART Raw Interrupt Status (RIS), offset 0x03c */ - -#define UART_RIS_RXRIS (1 << 4) /* Bit 4: UART Receive Raw Interrupt Status */ -#define UART_RIS_TXRIS (1 << 5) /* Bit 5: UART Transmit Raw Interrupt Status */ -#define UART_RIS_RTRIS (1 << 6) /* Bit 6: UART Receive Time-Out Raw Interrupt Status */ -#define UART_RIS_FERIS (1 << 7) /* Bit 7: UART Framing Error Raw Interrupt Status */ -#define UART_RIS_PERIS (1 << 8) /* Bit 8: UART Parity Error Raw Interrupt Status */ -#define UART_RIS_BERIS (1 << 9) /* Bit 9: UART Break Error Raw Interrupt Status */ -#define UART_RIS_OERIS (1 << 10) /* Bit 10: UART Overrun Error Raw Interrupt Status */ - -/* UART Masked Interrupt Status (MIS), offset 0x040 */ - -#define UART_MIS_RXMIS (1 << 4) /* Bit 4: UART Receive Masked Interrupt Status */ -#define UART_MIS_TXMIS (1 << 5) /* Bit 5: UART Transmit Masked Interrupt Status */ -#define UART_MIS_RTMIS (1 << 6) /* Bit 6: UART Receive Time-Out Masked Interrupt Status */ -#define UART_MIS_FEMIS (1 << 7) /* Bit 7: UART Framing Error Masked Interrupt Status */ -#define UART_MIS_PEMIS (1 << 8) /* Bit 8: UART Parity Error Masked Interrupt Status */ -#define UART_MIS_BEMIS (1 << 9) /* Bit 9: UART Break Error Masked Interrupt Status */ -#define UART_MIS_OEMIS (1 << 10) /* Bit 10: UART Overrun Error Masked Interrupt Status */ - -/* UART Interrupt Clear (ICR), offset 0x044 */ - -#define UART_ICR_RXIC (1 << 4) /* Bit 4: Receive Interrupt Clear */ -#define UART_ICR_TXIC (1 << 5) /* Bit 5: Transmit Interrupt Clear */ -#define UART_ICR_RTIC (1 << 6) /* Bit 6: Receive Time-Out Interrupt Clear */ -#define UART_ICR_FEIC (1 << 7) /* Bit 7: Framing Error Interrupt Clear */ -#define UART_ICR_PEIC (1 << 8) /* Bit 8: Parity Error Interrupt Clear */ -#define UART_ICR_BEIC (1 << 9) /* Bit 9: Break Error Interrupt Clear */ -#define UART_ICR_OEIC (1 << 10) /* Bit 10: Overrun Error Interrupt Clear - */ - -/* UART Peripheral Identification 4 (PERIPHID4), offset 0xfd0 */ - -#define UART_PERIPHID4_MASK (0xff) /* UART Peripheral ID Register[7:0] */ - -/* UART Peripheral Identification 5 (UARTPERIPHID5), offset 0xfd4 */ - -#define UART_PERIPHID5_MASK (0xff) /* UART Peripheral ID Register[15:8] */ - -/* UART Peripheral Identification 6 (UARTPERIPHID6), offset 0xfd8 */ - -#define UART_PERIPHID6_MASK (0xff) /* UART Peripheral ID Register[23:16] */ - -/* UART Peripheral Identification 7 (UARTPERIPHID7), offset 0xfdc */ - -#define UART_PERIPHID7_MASK (0xff) /* UART Peripheral ID Register[31:24] */ - -/* UART Peripheral Identification 0 (UARTPERIPHID0), offset 0xfe0 */ - -#define UART_PERIPHID0_MASK (0xff) /* UART Peripheral ID Register[7:0] */ - -/* UART Peripheral Identification 1 (UARTPERIPHID1), offset 0xfe4 */ - -#define UART_PERIPHID1_MASK (0xff) /* UART Peripheral ID Register[15:8] */ - -/* UART Peripheral Identification 2 (UARTPERIPHID2), offset 0xfe8 */ - -#define UART_PERIPHID2_MASK (0xff) /* UART Peripheral ID Register[23:16] */ - -/* UART Peripheral Identification 3 (UARTPERIPHID3), offset 0xfec */ - -#define UART_PERIPHID3_MASK (0xff) /* UART Peripheral ID Register[31:24] */ - -/* UART PrimeCell Identification 0 (CELLID0), offset 0xff0 */ - -#define UART_CELLID0_MASK (0xff) /* UART PrimeCell ID Register[7:0] */ - -/* UART PrimeCell Identification 1 (UARTPCELLID1), offset 0xff4 */ - -#define UART_CELLID1_MASK (0xff) /* UART PrimeCell ID Register[15:8] */ - -/* UART PrimeCell Identification 2 (UARTPCELLID2), offset 0xff8 */ - -#define UART_CELLID02MASK (0xff) /* UART PrimeCell ID Register[23:16] */ - -/* UART PrimeCell Identification 3 (UARTPCELLID3), offset 0xffc */ - -#define UART_CELLID3_MASK (0xff) /* UART PrimeCell ID Register[31:24] */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LM3S_LM3S_UART_H */ diff --git a/nuttx/binfmt/binfmt_exec.c b/nuttx/binfmt/binfmt_exec.c index 60e8d8efd..d5e274710 100644 --- a/nuttx/binfmt/binfmt_exec.c +++ b/nuttx/binfmt/binfmt_exec.c @@ -1,7 +1,7 @@ /**************************************************************************** * binfmt/binfmt_exec.c * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -75,7 +75,8 @@ * * Description: * This is a convenience function that wraps load_ and exec_module into - * one call. + * one call. The priority of the executed program is set to be the + * same as the priority of the calling thread. * * Input Parameter: * filename - Fulll path to the binary to be loaded @@ -94,8 +95,20 @@ int exec(FAR const char *filename, FAR const char **argv, FAR const struct symtab_s *exports, int nexports) { struct binary_s bin; + struct sched_param param; int ret; + /* Get the priority of this thread */ + + ret = sched_getparam(0, ¶m); + if (ret < 0) + { + bdbg("ERROR: sched_getparam failed: %d\n", errno); + return ERROR; + } + + /* Load the module into memory */ + memset(&bin, 0, sizeof(struct binary_s)); bin.filename = filename; bin.exports = exports; @@ -108,7 +121,9 @@ int exec(FAR const char *filename, FAR const char **argv, return ERROR; } - ret = exec_module(&bin, 50); + /* Then start the module at the priority of this thread */ + + ret = exec_module(&bin, param.sched_priority); if (ret < 0) { bdbg("ERROR: Failed to execute program '%s'\n", filename); diff --git a/nuttx/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h index 6df5190d2..480e82c09 100644 --- a/nuttx/include/nuttx/binfmt/binfmt.h +++ b/nuttx/include/nuttx/binfmt/binfmt.h @@ -228,7 +228,8 @@ int exec_module(FAR const struct binary_s *bin, int priority); * * Description: * This is a convenience function that wraps load_ and exec_module into - * one call. + * one call. The priority of the executed program is set to be the + * same as the priority of the calling thread. * * Input Parameter: * filename - Fulll path to the binary to be loaded diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h index ddb6880f4..d2ace79fa 100644 --- a/nuttx/include/unistd.h +++ b/nuttx/include/unistd.h @@ -160,6 +160,13 @@ EXTERN FAR char *getcwd(FAR char *buf, size_t size); EXTERN int unlink(FAR const char *pathname); EXTERN int rmdir(FAR const char *pathname); +/* Execution of programs from files */ + +#ifdef CONFIG_LIBC_EXECFUNCS +EXTERN int execl(FAR const char *path, ...); +EXTERN int execv(FAR const char *path, FAR char *const argv[]); +#endif + /* Other */ EXTERN int getopt(int argc, FAR char *const argv[], FAR const char *optstring); diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig index 0ae56ac57..699b3ebb2 100644 --- a/nuttx/libc/Kconfig +++ b/nuttx/libc/Kconfig @@ -71,6 +71,54 @@ config EOL_IS_EITHER_CRLF endchoice +config LIBC_EXECFUNCS + bool "Enable exec[l|v] Support" + default n + depends on !BINFMT_DISABLE + ---help--- + Enable support for the exec[l|v] family of functions that can be + used to start other programs, terminating the current program. + Typical usage is (1) first call vfork() to create a new thread, then + (2) call exec[l|v] to replace the new thread with a program from the + file system. + + NOTE 1: This two step process start is completely unnecessary in + NuttX and is provided only for compatibily with Unix systems. These + functions are essentially just wrapper functions that (1) call the + non-standard binfmt function 'exec', and then (2) exit(0). Since + the new thread will be terminated by the exec[l|v] call, it really + served no purpose other than to suport Unix compatility. + + NOTE 2: Support for exec[l|v] is conditional because is requires + additional support for symbol tables that will not be available in + the typical system. + +if LIBC_EXECFUNCS + +config EXECFUNCS_SYMTAB + string "Symbol table used by exec[l|v]" + default "g_symtab" + ---help--- + The exec[l|v] functions are wrapper functions that (1) call the non- + standard binfmt function 'exec', and then (2) exit(0). The binfmt + function 'exec' needs to have (1) a symbol table that provides the + list of symbols exported by the base code, and (2) the number of + symbols in that table. This selection provides the name of that + symbol table. + +config EXECFUNCS_NSYMBOLS + int "Number of Symbols in the Table" + default 0 + ---help--- + The exec[l|v] functions are wrapper functions that (1) call the non- + standard binfmt function 'exec', and then (2) exit(0). The binfmt + function 'exec' needs to have (1) a symbol table that provides the + list of symbols exported by the base code, and (2) the number of + symbols in that table. This selection provides the number of + symbols in the symbol table. + +endif + config LIBC_STRERROR bool "Enable strerror" default n diff --git a/nuttx/libc/unistd/Make.defs b/nuttx/libc/unistd/Make.defs index 67fce9b1d..3811673bf 100644 --- a/nuttx/libc/unistd/Make.defs +++ b/nuttx/libc/unistd/Make.defs @@ -41,6 +41,10 @@ ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) ifneq ($(CONFIG_DISABLE_ENVIRON),y) CSRCS += lib_chdir.c lib_getcwd.c endif + +ifeq ($(CONFIG_LIBC_EXECFUNCS),y) +CSRCS += lib_execl.c lib_execv.c +endif endif # Add the unistd directory to the build diff --git a/nuttx/libc/unistd/lib_execl.c b/nuttx/libc/unistd/lib_execl.c new file mode 100644 index 000000000..ac3147343 --- /dev/null +++ b/nuttx/libc/unistd/lib_execl.c @@ -0,0 +1,146 @@ +/**************************************************************************** + * libc/unistd/lib_execl.c + * + * Copyright (C) 2013 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#ifdef CONFIG_LIBC_EXECFUNCS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: execl + * + * Description: + * The standard 'exec' family of functions will replace the current process + * image with a new process image. The new image will be constructed from a + * regular, executable file called the new process image file. There will + * be no return from a successful exec, because the calling process image + * is overlaid by the new process image. + * + * Simplified 'execl()' and 'execv()' functions are provided by NuttX for + * compatibility. NuttX is a tiny embedded RTOS that does not support + * processes and hence the concept of overlaying a tasks process image with + * a new process image does not make any sense. In NuttX, these functions + * are wrapper functions that: + * + * 1. Call the non-standard binfmt function 'exec', and then + * 2. exit(0). + * + * Note the inefficiency when 'exec[l|v]()' is called in the normal, two- + * step process: (1) first call vfork() to create a new thread, then (2) + * call 'exec[l|v]()' to replace the new thread with a program from the + * file system. Since the new thread will be terminated by the + * 'exec[l|v]()' call, it really served no purpose other than to suport + * Unix compatility. + * + * The non-standard binfmt function 'exec()' needs to have (1) a symbol + * table that provides the list of symbols exported by the base code, and + * (2) the number of symbols in that table. This information is currently + * provided to 'exec()' from 'exec[l|v]()' via NuttX configuration settings: + * + * CONFIG_LIBC_EXECFUNCS : Enable exec[l|v] Support + * CONFIG_EXECFUNCS_SYMTAB : Symbol table used by exec[l|v] + * CONFIG_EXECFUNCS_NSYMBOLS : Number of Symbols in the Table + * + * As a result of the above, the current implementations of 'execl()' and + * 'execv()' suffer from some incompatibilities that may or may not be + * addressed in a future version of NuttX. Other than just being an + * inefficient use of MCU resource, the most serious of these is that + * the exec'ed task will not have the same task ID as the vfork'ed + * function. So the parent function cannot know the ID of the exec'ed + * task. + * + * Input Parameters: + * path - The path to the program to be executed. If CONFIG_BINFMT_EXEPATH + * is defined in the configuration, then this may be a relative path + * from the current working directory. Otherwise, path must be the + * absolute path to the program. + * arg0,... - A list of the string arguments to be recevied by the + * program. Zero indicates the end of the list. + * + * Returned Value: + * This function does not return on success. On failure, it will return + * -1 (ERROR) and will set the 'errno' value appropriately. + * + ****************************************************************************/ + +int execl(FAR const char *path, ...) +{ + FAR char *argv[CONFIG_MAX_TASK_ARGS+1]; + va_list ap; + int argc; + + /* Collect the arguments into the argv[] array */ + + va_start(ap, path); + for (argc = 0; argc < CONFIG_MAX_TASK_ARGS; argc++) + { + argv[argc] = va_arg(ap, FAR char *); + if (argv[argc] == NULL) + { + break; + } + } + + argv[CONFIG_MAX_TASK_ARGS] = NULL; + va_end(ap); + + /* Then let execv() do the real work */ + + return execv(path, (char * const *)&argv); +} + +#endif /* CONFIG_LIBC_EXECFUNCS */ \ No newline at end of file diff --git a/nuttx/libc/unistd/lib_execv.c b/nuttx/libc/unistd/lib_execv.c new file mode 100644 index 000000000..cad8ee307 --- /dev/null +++ b/nuttx/libc/unistd/lib_execv.c @@ -0,0 +1,168 @@ +/**************************************************************************** + * libc/unistd/lib_execv.c + * + * Copyright (C) 2013 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +#ifdef CONFIG_LIBC_EXECFUNCS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* If CONFIG_LIBC_EXECFUNCS is defined in the configuration, then the + * following must also be defined: + */ + +/* Symbol table used by exec[l|v] */ + +#ifndef CONFIG_EXECFUNCS_SYMTAB +# error "CONFIG_EXECFUNCS_SYMTAB must be defined" +#endif + +/* Number of Symbols in the Table */ + +#ifndef CONFIG_EXECFUNCS_NSYMBOLS +# error "CONFIG_EXECFUNCS_NSYMBOLS must be defined" +#endif + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +extern struct symtab_s CONFIG_EXECFUNCS_SYMTAB; + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: execv + * + * Description: + * The standard 'exec' family of functions will replace the current process + * image with a new process image. The new image will be constructed from a + * regular, executable file called the new process image file. There will + * be no return from a successful exec, because the calling process image + * is overlaid by the new process image. + * + * Simplified 'execl()' and 'execv()' functions are provided by NuttX for + * compatibility. NuttX is a tiny embedded RTOS that does not support + * processes and hence the concept of overlaying a tasks process image with + * a new process image does not make any sense. In NuttX, these functions + * are wrapper functions that: + * + * 1. Call the non-standard binfmt function 'exec', and then + * 2. exit(0). + * + * Note the inefficiency when 'exec[l|v]()' is called in the normal, two- + * step process: (1) first call vfork() to create a new thread, then (2) + * call 'exec[l|v]()' to replace the new thread with a program from the + * file system. Since the new thread will be terminated by the + * 'exec[l|v]()' call, it really served no purpose other than to suport + * Unix compatility. + * + * The non-standard binfmt function 'exec()' needs to have (1) a symbol + * table that provides the list of symbols exported by the base code, and + * (2) the number of symbols in that table. This information is currently + * provided to 'exec()' from 'exec[l|v]()' via NuttX configuration settings: + * + * CONFIG_LIBC_EXECFUNCS : Enable exec[l|v] Support + * CONFIG_EXECFUNCS_SYMTAB : Symbol table used by exec[l|v] + * CONFIG_EXECFUNCS_NSYMBOLS : Number of Symbols in the Table + * + * As a result of the above, the current implementations of 'execl()' and + * 'execv()' suffer from some incompatibilities that may or may not be + * addressed in a future version of NuttX. Other than just being an + * inefficient use of MCU resource, the most serious of these is that + * the exec'ed task will not have the same task ID as the vfork'ed + * function. So the parent function cannot know the ID of the exec'ed + * task. + * + * Input Parameters: + * path - The path to the program to be executed. If CONFIG_BINFMT_EXEPATH + * is defined in the configuration, then this may be a relative path + * from the current working directory. Otherwise, path must be the + * absolute path to the program. + * argv - A pointer to an array of string arguments. The end of the + * array is indicated with a NULL entry. + * + * Returned Value: + * This function does not return on success. On failure, it will return + * -1 (ERROR) and will set the 'errno' value appropriately. + * + ****************************************************************************/ + +int execv(FAR const char *path, FAR char *const argv[]) +{ + int ret; + + /* Start the task */ + + ret = exec(path, (FAR const char **)argv, + &CONFIG_EXECFUNCS_SYMTAB, CONFIG_EXECFUNCS_NSYMBOLS); + + if (ret < 0) + { + sdbg("exec failed: %d\n", errno); + return ERROR; + } + + /* Then exit */ + + exit(0); + + /* We should not get here, but might be needed by some compilers. Other, + * smarter compilers might complain that this code is unreachable. You just + * can't win. + */ + + return ERROR; +} + +#endif /* CONFIG_LIBC_EXECFUNCS */ \ No newline at end of file diff --git a/nuttx/tools/cfgdefine.c b/nuttx/tools/cfgdefine.c index ee1dd4003..f026a186f 100644 --- a/nuttx/tools/cfgdefine.c +++ b/nuttx/tools/cfgdefine.c @@ -64,6 +64,7 @@ static const char *dequote_list[] = /* NuttX */ "CONFIG_USER_ENTRYPOINT", /* Name of entry point function */ + "CONFIG_EXECFUNCS_SYMTAB", /* Symbol table used by exec[l|v] */ /* NxWidgets/NxWM */ -- cgit v1.2.3