Add support for the Texas Instruments CC2538 ARM Cortex-M3 MCU and developer kit.

dev/timer
Ian Martin 9 years ago
parent 1258183791
commit 0605a7eb95

@ -0,0 +1,4 @@
# Tell the Makefile.base which module to build:
MODULE = $(BOARD)_base
include $(RIOTBASE)/Makefile.base

@ -0,0 +1 @@
FEATURES_PROVIDED = periph_gpio

@ -0,0 +1,41 @@
# Define the cpu used by the CC2538DK board:
export CPU = cc2538
export CPU_MODEL ?= cc2538nf53
# Define tools used for building the project:
export PREFIX ?= arm-none-eabi-
export CC = $(PREFIX)gcc
export AR = $(PREFIX)ar
export AS = $(PREFIX)as
export LINK = $(PREFIX)gcc
export SIZE = $(PREFIX)size
export OBJCOPY = $(PREFIX)objcopy
export OBJDUMP = $(PREFIX)objdump
export TERMPROG ?= $(RIOTBASE)/dist/tools/pyterm/pyterm
# Define the flash-tool and default port:
export FLASHER ?= python $(RIOTBOARD)/$(BOARD)/dist/cc2538-bsl.py
export PORT ?= /dev/ttyUSB1
# Define build specific options:
export CPU_USAGE = -mcpu=cortex-m3
export ASFLAGS += -ggdb -g3 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian
export CFLAGS += $(ASFLAGS) -std=gnu99 -mthumb -mthumb-interwork -nostartfiles -Os -Wall -Wstrict-prototypes -ffunction-sections -fdata-sections -fno-builtin
export LINKFLAGS += $(CFLAGS) -static -lgcc -T$(LINKERSCRIPT) -L$(RIOTCPU)/$(CPU)
export OFLAGS += -O binary --gap-fill 0xff
export FFLAGS += -p "$(PORT)" -e -w -v bin/$(BOARD)/$(APPLICATION).hex
export TERMFLAGS += -p "$(PORT)"
export OBJDUMPFLAGS += --disassemble --source --disassembler-options=force-thumb
# Use the nano-specs of the NewLib when available:
ifeq ($(shell $(LINK) -specs=nano.specs -E - 2>/dev/null >/dev/null </dev/null ; echo $$?),0)
export LINKFLAGS += -specs=nano.specs -lc -lnosys
endif
# Export board specific includes to the global includes-listing:
export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include

@ -0,0 +1,59 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup board_cc2538dk
* @{
*
* @file board.c
* @brief Board specific implementations for the CC2538DK board
*
* @author Ian Martin <ian@locicontrols.com>
*/
#include <stdio.h>
#include "board.h"
#include "cpu.h"
#include "ioc.h"
#include "lpm.h"
#include "cc2538-gpio.h"
static void led_init_helper(int gpio_num) {
gpio_software_control(gpio_num);
gpio_dir_output(gpio_num);
/* Enable output without any internal pull resistors: */
IOC_PXX_OVER[gpio_num] = IOC_OVERRIDE_OE;
}
/**
* @brief Initialize the SmartRF06's on-board LEDs
*/
void led_init(void)
{
led_init_helper(LED_RED_GPIO);
led_init_helper(LED_GREEN_GPIO);
led_init_helper(LED_YELLOW_GPIO);
led_init_helper(LED_ORANGE_GPIO);
}
/**
* @brief Initialize the SmartRF06 board
*/
void board_init(void)
{
/* initialize the CPU */
cpu_init();
/* initialize the boards LEDs */
led_init();
}
/** @} */

@ -0,0 +1,100 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup board_cc2538dk CC2538DK
* @ingroup boards
* @brief Support for the Texas Instruments CC2538DK board.
* @{
*
* @file
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef __BOARD_H
#define __BOARD_H
#include "cpu.h"
#include "periph/gpio.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* Define the nominal CPU core clock in this board
*/
#define F_CPU XOSC32M_FREQ
/**
* Assign the hardware timer
*/
#define HW_TIMER TIMER_0
/**
* @name Define UART device and baudrate for stdio
* @{
*/
#define STDIO UART_0
#define STDIO_BAUDRATE 115200
#define STDIO_RX_BUFSIZE (64U)
/** @} */
/**
* @name Macros for controlling the on-board LEDs.
* @{
*/
#define LED_RED_GPIO GPIO_PC0 /**< Red LED GPIO pin */
#define LED_YELLOW_GPIO GPIO_PC1 /**< Yellow LED GPIO pin */
#define LED_GREEN_GPIO GPIO_PC2 /**< Green LED GPIO pin */
#define LED_ORANGE_GPIO GPIO_PC3 /**< Orange LED GPIO pin */
#define LED_RED_ON cc2538_gpio_set(LED_GREEN_GPIO)
#define LED_RED_OFF cc2538_gpio_clear(LED_GREEN_GPIO)
#define LED_RED_TOGGLE cc2538_gpio_toggle(LED_GREEN_GPIO)
#define LED_YELLOW_ON cc2538_gpio_set(LED_YELLOW_GPIO)
#define LED_YELLOW_OFF cc2538_gpio_clear(LED_YELLOW_GPIO)
#define LED_YELLOW_TOGGLE cc2538_gpio_toggle(LED_YELLOW_GPIO)
#define LED_GREEN_ON cc2538_gpio_set(LED_GREEN_GPIO)
#define LED_GREEN_OFF cc2538_gpio_clear(LED_GREEN_GPIO)
#define LED_GREEN_TOGGLE cc2538_gpio_toggle(LED_GREEN_GPIO)
#define LED_ORANGE_ON cc2538_gpio_set(LED_ORANGE_GPIO)
#define LED_ORANGE_OFF cc2538_gpio_clear(LED_ORANGE_GPIO)
#define LED_ORANGE_TOGGLE cc2538_gpio_toggle(LED_ORANGE_GPIO)
/* Default to red if the color is not specified: */
#define LED_ON LED_RED_ON
#define LED_OFF LED_RED_OFF
#define LED_TOGGLE LED_RED_TOGGLE
/** @} */
/**
* @name Flash Customer Configuration Area (CCA) parameters
* @{
*/
#define UPDATE_CCA 1
#define CCA_BACKDOOR_ENABLE 1
#define CCA_BACKDOOR_PORT_A_PIN 3 /**< Select button */
#define CCA_BACKDOOR_ACTIVE_LEVEL 0 /**< Active low */
/** @} */
/**
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
*/
void board_init(void);
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /** __BOARD_H */
/** @} */

@ -0,0 +1,186 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup board_cc2538dk
* @{
*
* @file
* @brief Peripheral MCU configuration for the CC2538DK board
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef __PERIPH_CONF_H
#define __PERIPH_CONF_H
#include "gptimer.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Timer peripheral configuration
* @{
*/
#define TIMER_NUMOF GPTIMER_NUMOF
#define TIMER_0_EN 1
#define TIMER_1_EN 1
#define TIMER_2_EN 1
#define TIMER_3_EN 1
#define TIMER_IRQ_PRIO 1
/* Timer 0 configuration */
#define TIMER_0_DEV GPTIMER0
#define TIMER_0_CHANNELS NUM_CHANNELS_PER_GPTIMER
#define TIMER_0_MAX_VALUE 0xffffffff
#define TIMER_0_IRQn_1 GPTIMER_0A_IRQn
#define TIMER_0_IRQn_2 GPTIMER_0B_IRQn
/* Timer 1 configuration */
#define TIMER_1_DEV GPTIMER1
#define TIMER_1_CHANNELS NUM_CHANNELS_PER_GPTIMER
#define TIMER_1_MAX_VALUE 0xffffffff
#define TIMER_1_IRQn_1 GPTIMER_1A_IRQn
#define TIMER_1_IRQn_2 GPTIMER_1B_IRQn
/* Timer 2 configuration */
#define TIMER_2_DEV GPTIMER2
#define TIMER_2_CHANNELS NUM_CHANNELS_PER_GPTIMER
#define TIMER_2_MAX_VALUE 0xffffffff
#define TIMER_2_IRQn_1 GPTIMER_2A_IRQn
#define TIMER_2_IRQn_2 GPTIMER_2B_IRQn
/* Timer 3 configuration */
#define TIMER_3_DEV GPTIMER3
#define TIMER_3_CHANNELS NUM_CHANNELS_PER_GPTIMER
#define TIMER_3_MAX_VALUE 0xffffffff
#define TIMER_3_IRQn_1 GPTIMER_3A_IRQn
#define TIMER_3_IRQn_2 GPTIMER_3B_IRQn
/** @} */
/**
* @name UART configuration
* @{
*/
#define UART_NUMOF 1
#define UART_0_EN 1
#define UART_1_EN 0
#define UART_2_EN 0
#define UART_3_EN 0
#define UART_IRQ_PRIO 1
/* UART 0 device configuration */
#define UART_0_DEV UART0
#define UART_0_IRQ UART0_IRQn
/* UART 0 pin configuration */
#define UART_0_TX_PIN GPIO_PA1
#define UART_0_RX_PIN GPIO_PA0
/* UART 1 device configuration */
#define UART_1_DEV UART1
#define UART_1_IRQ UART1_IRQn
/* UART 1 pin configuration */
#define UART_1_RTS_PIN GPIO_PD3
#define UART_1_CTS_PIN GPIO_PB0
/** @} */
/**
* @name Random Number Generator configuration
* @{
*/
#define RANDOM_NUMOF 1
/** @} */
/**
* @name GPIO configuration
* @{
*/
#define GPIO_NUMOF 32
#define GPIO_IRQ_PRIO 1
#define GPIO_0_EN 1
#define GPIO_1_EN 1
#define GPIO_2_EN 1
#define GPIO_3_EN 1
#define GPIO_4_EN 1
#define GPIO_5_EN 1
#define GPIO_6_EN 1
#define GPIO_7_EN 1
#define GPIO_8_EN 1
#define GPIO_9_EN 1
#define GPIO_10_EN 1
#define GPIO_11_EN 1
#define GPIO_12_EN 1
#define GPIO_13_EN 1
#define GPIO_14_EN 1
#define GPIO_15_EN 1
#define GPIO_16_EN 1
#define GPIO_17_EN 1
#define GPIO_18_EN 1
#define GPIO_19_EN 1
#define GPIO_20_EN 1
#define GPIO_21_EN 1
#define GPIO_22_EN 1
#define GPIO_23_EN 1
#define GPIO_24_EN 1
#define GPIO_25_EN 1
#define GPIO_26_EN 1
#define GPIO_27_EN 1
#define GPIO_28_EN 1
#define GPIO_29_EN 1
#define GPIO_30_EN 1
#define GPIO_31_EN 1
/* GPIO channel configuration */
#define GPIO_0_PIN GPIO_PA0
#define GPIO_1_PIN GPIO_PA1
#define GPIO_2_PIN GPIO_PA2
#define GPIO_3_PIN GPIO_PA3
#define GPIO_4_PIN GPIO_PA4
#define GPIO_5_PIN GPIO_PA5
#define GPIO_6_PIN GPIO_PA6
#define GPIO_7_PIN GPIO_PA7
#define GPIO_8_PIN GPIO_PB0
#define GPIO_9_PIN GPIO_PB1
#define GPIO_10_PIN GPIO_PB2
#define GPIO_11_PIN GPIO_PB3
#define GPIO_12_PIN GPIO_PB4
#define GPIO_13_PIN GPIO_PB5
#define GPIO_14_PIN GPIO_PB6
#define GPIO_15_PIN GPIO_PB7
#define GPIO_16_PIN GPIO_PC0
#define GPIO_17_PIN GPIO_PC1
#define GPIO_18_PIN GPIO_PC2
#define GPIO_19_PIN GPIO_PC3
#define GPIO_20_PIN GPIO_PC4
#define GPIO_21_PIN GPIO_PC5
#define GPIO_22_PIN GPIO_PC6
#define GPIO_23_PIN GPIO_PC7
#define GPIO_24_PIN GPIO_PD0
#define GPIO_25_PIN GPIO_PD1
#define GPIO_26_PIN GPIO_PD2
#define GPIO_27_PIN GPIO_PD3
#define GPIO_28_PIN GPIO_PD4
#define GPIO_29_PIN GPIO_PD5
#define GPIO_30_PIN GPIO_PD6
#define GPIO_31_PIN GPIO_PD7
/** @} */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* __PERIPH_CONF_H */
/** @} */

@ -0,0 +1,7 @@
# Define the module that is built:
MODULE = cpu
# Add a list of subdirectories, that should also be built:
DIRS = periph $(CORTEX_COMMON)
include $(RIOTBASE)/Makefile.base

@ -0,0 +1,35 @@
# This CPU implementation is using the new core/CPU interface:
export CFLAGS += -DCOREIF_NG=1
# Tell the build system that the CPU depends on the Cortex-M common files:
export USEMODULE += cortex-m3_common
# Define path to cortex-m common module, which is needed for this CPU:
export CORTEX_COMMON = $(RIOTCPU)/cortex-m3_common/
# Define the linker script to use for this CPU:
export LINKERSCRIPT = $(RIOTCPU)/$(CPU)/$(CPU_MODEL)_linkerscript.ld
# Include CPU specific includes:
export INCLUDES += -I$(RIOTCPU)/$(CPU)/include
# Explicitly tell the linker to link the syscalls and startup code.
# Without this the interrupt vectors will not be linked correctly!
export UNDEF += $(BINDIR)cpu/syscalls.o
export UNDEF += $(BINDIR)cpu/startup.o
# Export the peripheral drivers to be linked into the final binary:
export USEMODULE += periph
# this CPU implementation makes use of the ringbuffer, so include the lib module
export USEMODULE += lib
# CPU depends on the cortex-m common module, so include it:
include $(CORTEX_COMMON)Makefile.include
# Avoid overriding the default rule:
all:
# Rule to generate assembly listings from ELF files:
%.lst: %.elf
$(OBJDUMP) $(OBJDUMPFLAGS) $< > $@

@ -31,17 +31,8 @@ OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
OUTPUT_ARCH(arm)
SEARCH_DIR(.)
/* Memory Spaces Definitions */
MEMORY
{
rom (rx) : ORIGIN = 0x00080000, LENGTH = 0x00080000 /* Flash, 512K */
sram0 (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00010000 /* sram0, 64K */
sram1 (rwx) : ORIGIN = 0x20080000, LENGTH = 0x00008000 /* sram1, 32K */
ram (rwx) : ORIGIN = 0x20070000, LENGTH = 0x00018000 /* sram, 96K */
}
/* The stack size used by the application. NOTE: you need to adjust */
STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 0x2000 ;
STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : 2K ;
/* Section Definitions */
SECTIONS
@ -141,4 +132,9 @@ SECTIONS
. = ALIGN(4);
_end = . ;
}
.flashcca :
{
KEEP(*(.flashcca))
} > cca
}

@ -0,0 +1,30 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup cpu_cc2538
* @{
*
* @file cc2538nf11_linkerscript.ld
* @brief Linker script for the CC2538NF11 model MCU
*
* @author Ian Martin <ian@locicontrols.com>
*/
/* Memory Space Definitions: */
MEMORY
{
rom (rx ) : ORIGIN = 0x00200000, LENGTH = 128K - 44
cca (rx ) : ORIGIN = 0x0027ffd4, LENGTH = 44
sram1 (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
ram (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
}
INCLUDE cc2538_linkerscript.ld
/* @} */

@ -0,0 +1,31 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup cpu_cc2538
* @{
*
* @file cc2538nf23_linkerscript.ld
* @brief Linker script for the CC2538NF23 and CC2538SF23 model MCUs
*
* @author Ian Martin <ian@locicontrols.com>
*/
/* Memory Space Definitions: */
MEMORY
{
rom (rx ) : ORIGIN = 0x00200000, LENGTH = 256K - 44
cca (rx ) : ORIGIN = 0x0027ffd4, LENGTH = 44
sram0 (rwx) : ORIGIN = 0x20000000, LENGTH = 16K /* Lost in PM2 and PM3 */
sram1 (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K
}
INCLUDE cc2538_linkerscript.ld
/* @} */

@ -0,0 +1,31 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup cpu_cc2538
* @{
*
* @file cc2538nf53_linkerscript.ld
* @brief Linker script for the CC2538NF53 and CC2538SF53 model MCUs
*
* @author Ian Martin <ian@locicontrols.com>
*/
/* Memory Space Definitions: */
MEMORY
{
rom (rx ) : ORIGIN = 0x00200000, LENGTH = 512K - 44
cca (rx ) : ORIGIN = 0x0027ffd4, LENGTH = 44
sram0 (rwx) : ORIGIN = 0x20000000, LENGTH = 16K /* Lost in PM2 and PM3 */
sram1 (rwx) : ORIGIN = 0x20004000, LENGTH = 16K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K
}
INCLUDE cc2538_linkerscript.ld
/* @} */

@ -0,0 +1,90 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_cc2538
* @{
*
* @file cpu.c
* @brief Implementation of the CPU initialization
*
* @author Ian Martin <ian@locicontrols.com>
* @}
*/
#include "cpu.h"
#include "sys-ctrl.h"
#define BIT(n) ( 1UL << (n) )
/* Select CLOCK_CTRL register bit masks: */
#define OSC32K BIT(24) /**< 32-kHz clock oscillator selection */
#define OSC_PD BIT(17) /**< Oscillator power-down */
#define OSC BIT(16) /**< System clock oscillator selection */
/* CLOCK_CTRL register field offsets: */
#define IO_DIV_SHIFT 8
#define SYS_DIV_SHIFT 0
#define CLOCK_STA_MASK ( OSC32K | OSC )
static void cpu_clock_init(void);
/**
* @brief Initialize the CPU, set IRQ priorities
*/
void cpu_init(void)
{
/* configure the vector table location to internal flash */
SCB->VTOR = FLASH_BASE;
/* initialize the clock system */
cpu_clock_init();
/* set pendSV interrupt to lowest possible priority */
NVIC_SetPriority(PendSV_IRQn, 0xff);
}
/**
* @brief Configure the controllers clock system
*/
static void cpu_clock_init(void)
{
const uint32_t CLOCK_CTRL_VALUE =
OSC_PD /**< Power down the oscillator not selected by OSC bit (hardware-controlled when selected). */
| (1 << IO_DIV_SHIFT) /**< 16 MHz IO_DIV */
| (1 << SYS_DIV_SHIFT) /**< 16 MHz SYS_DIV */
#if !SYS_CTRL_OSC32K_USE_XTAL
| OSC32K /**< Use internal RC oscillator. */
#endif
;
#if SYS_CTRL_OSC32K_USE_XTAL
/* Set the XOSC32K_Q pads to analog for the external crystal: */
gpio_software_control(GPIO_PD6);
gpio_dir_input(GPIO_PD6);
IOC_PXX_OVER[GPIO_PD6] = IOC_OVERRIDE_ANA;
gpio_software_control(GPIO_PD7);
gpio_dir_input(GPIO_PD7);
IOC_PXX_OVER[GPIO_PD7] = IOC_OVERRIDE_ANA;
#endif
/* Configure the clock settings: */
SYS_CTRL->CLOCK_CTRL = CLOCK_CTRL_VALUE;
/* Wait for the new clock settings to take effect: */
while ( (SYS_CTRL->CLOCK_STA ^ CLOCK_CTRL_VALUE) & CLOCK_STA_MASK );
#if SYS_CTRL_OSC32K_USE_XTAL
/* Wait for the 32-kHz crystal oscillator to stabilize: */
while ( SYS_CTRL->CLOCK_STAbits.SYNC_32K);
while (!SYS_CTRL->CLOCK_STAbits.SYNC_32K);
#endif
}

@ -0,0 +1,10 @@
/**
* @defgroup cpu_cc2538 Texas Instruments CC2538
* @ingroup cpu
* @brief Texas Instruments CC2538 Cortex-M3 MCU specific code
*/
/**
* @defgroup cpu_cc2538_definitions Texas Instruments CC2538 Definitions
* @ingroup cpu_cc2538
*/

@ -7,7 +7,7 @@
*/
/**
* @ingroup cpu_sam3x8e
* @ingroup cpu_cc2538
* @{
*
* @file hwtimer_arch.c
@ -23,7 +23,7 @@
#include "arch/hwtimer_arch.h"
#include "board.h"
#include "periph/timer.h"
#include "thread.h"
#include "hwtimer_cpu.h"
void irq_handler(int channel);
@ -33,7 +33,7 @@ void (*timeout_handler)(int);
void hwtimer_arch_init(void (*handler)(int), uint32_t fcpu)
{
timeout_handler = handler;
timer_init(HW_TIMER, 1, &irq_handler);
timer_init(HW_TIMER, HWTIMER_SPEED / 1000000, &irq_handler);
}
void hwtimer_arch_enable_interrupt(void)
@ -69,5 +69,4 @@ unsigned long hwtimer_arch_now(void)
void irq_handler(int channel)
{
timeout_handler((short)(channel));
thread_yield();
}

@ -0,0 +1,231 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup cpu_cc2538
* @{
*
* @file cc2538-gpio.h
* @brief Driver for the cc2538 GPIO controller
*
* Header file with register and macro declarations for the cc2538 GPIO module
*
* @author Ian Martin <ian@locicontrols.com>
*
* @defgroup cc2538-gpio CC2538 General-Purpose I/O
* @{
*/
#ifndef CC2538_GPIO_H
#define CC2538_GPIO_H
#include <stdint.h>
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
/** @name Numeric representation of the four GPIO ports
* @{
*/
enum {
PORT_A = 0,
PORT_B = 1,
PORT_C = 2,
PORT_D = 3,
};
/** @} */
#define GPIO_PORT_SHIFT 3 /**< Right-shift amount to obtain the port number from a GPIO number */
#define GPIO_BITS_PER_PORT ( 1 << GPIO_PORT_SHIFT ) /**< Number of bits per GPIO port (8) */
#define GPIO_BIT_MASK ( GPIO_BITS_PER_PORT - 1 ) /**< Mask to obtain the bit number from a GPIO number */
/**
* @brief Generate a bit mask in which only the specified bit is high.
*
* @param[in] n Number of the bit to set high in the mask.
*
* @return A bit mask in which bit n is high.
*/
#define GPIO_PIN_MASK(n) ( 1 << (n) )
/**
* @brief Extract the GPIO port number (0-3) from a GPIO number (0-31)
*
* @param[in] gpio_num GPIO number (0-31)
*
* @return Corresponding GPIO port number (0-3)
*/
#define GPIO_NUM_TO_PORT_NUM(gpio_num) ( (gpio_num) >> GPIO_PORT_SHIFT )
/**
* @brief Extract the GPIO port bit number (0-7) from a GPIO number (0-31)
*
* @param[in] gpio_num GPIO number (0-31)
*
* @return Corresponding GPIO port bit number (0-7)
*/
#define GPIO_BIT_NUM(gpio_num) ( (gpio_num) & GPIO_BIT_MASK )
/**
* @brief Generate a GPIO number given a port and bit number
*
* @param[in] port_num GPIO port (PORT_A, PORT_B, PORT_C, or PORT_D)
* @param[in] bit_num GPIO bit number (0-7)
*
* @return Corresponding GPIO number (0-31)
*/
#define GPIO_PXX_TO_NUM(port_num, bit_num) ( ((port_num) << GPIO_PORT_SHIFT) | (bit_num) )
/**
* @brief Obtain the GPIO port instance given a GPIO number (0-31)
*
* @param[in] gpio_num GPIO number (0-31)
*
* @return Corresponding GPIO port instance
*/
#define GPIO_NUM_TO_DEV(gpio_num) ( GPIO_A + GPIO_NUM_TO_PORT_NUM(gpio_num) )
/**
* @brief Enable hardware (peripheral) control for a given GPIO pin number
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define gpio_hardware_control(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->AFSEL |= GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/**
* @brief Enable software control for a given GPIO pin number
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define gpio_software_control(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->AFSEL &= ~GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/**
* @brief Configure the given GPIO as an output
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define gpio_dir_output(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->DIR |= GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/**
* @brief Configure the given GPIO as an input
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define gpio_dir_input(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->DIR &= ~GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/**
* @brief Set a specific GPIO output pin high
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define cc2538_gpio_set(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->DATA |= GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/**
* @brief Set a specific GPIO output pin low
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define cc2538_gpio_clear(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->DATA &= ~GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/**
* @brief Toggle the output state of a specific GPIO pin
*
* @param[in] gpio_num GPIO number (0-31)
*/
#define cc2538_gpio_toggle(gpio_num) ( GPIO_NUM_TO_DEV(gpio_num)->DATA ^= GPIO_PIN_MASK(GPIO_BIT_NUM(gpio_num)) )
/** @name Unique names for each GPIO port/pin combination
* @{
*/
enum {
GPIO_PA0 = GPIO_PXX_TO_NUM(PORT_A, 0), /**< PA0 */
GPIO_PA1 = GPIO_PXX_TO_NUM(PORT_A, 1), /**< PA1 */
GPIO_PA2 = GPIO_PXX_TO_NUM(PORT_A, 2), /**< PA2 */
GPIO_PA3 = GPIO_PXX_TO_NUM(PORT_A, 3), /**< PA3 */
GPIO_PA4 = GPIO_PXX_TO_NUM(PORT_A, 4), /**< PA4 */
GPIO_PA5 = GPIO_PXX_TO_NUM(PORT_A, 5), /**< PA5 */
GPIO_PA6 = GPIO_PXX_TO_NUM(PORT_A, 6), /**< PA6 */
GPIO_PA7 = GPIO_PXX_TO_NUM(PORT_A, 7), /**< PA7 */
GPIO_PB0 = GPIO_PXX_TO_NUM(PORT_B, 0), /**< PB0 */
GPIO_PB1 = GPIO_PXX_TO_NUM(PORT_B, 1), /**< PB1 */
GPIO_PB2 = GPIO_PXX_TO_NUM(PORT_B, 2), /**< PB2 */
GPIO_PB3 = GPIO_PXX_TO_NUM(PORT_B, 3), /**< PB3 */
GPIO_PB4 = GPIO_PXX_TO_NUM(PORT_B, 4), /**< PB4 */
GPIO_PB5 = GPIO_PXX_TO_NUM(PORT_B, 5), /**< PB5 */
GPIO_PB6 = GPIO_PXX_TO_NUM(PORT_B, 6), /**< PB6 */
GPIO_PB7 = GPIO_PXX_TO_NUM(PORT_B, 7), /**< PB7 */
GPIO_PC0 = GPIO_PXX_TO_NUM(PORT_C, 0), /**< PC0 */
GPIO_PC1 = GPIO_PXX_TO_NUM(PORT_C, 1), /**< PC1 */
GPIO_PC2 = GPIO_PXX_TO_NUM(PORT_C, 2), /**< PC2 */
GPIO_PC3 = GPIO_PXX_TO_NUM(PORT_C, 3), /**< PC3 */
GPIO_PC4 = GPIO_PXX_TO_NUM(PORT_C, 4), /**< PC4 */
GPIO_PC5 = GPIO_PXX_TO_NUM(PORT_C, 5), /**< PC5 */
GPIO_PC6 = GPIO_PXX_TO_NUM(PORT_C, 6), /**< PC6 */
GPIO_PC7 = GPIO_PXX_TO_NUM(PORT_C, 7), /**< PC7 */
GPIO_PD0 = GPIO_PXX_TO_NUM(PORT_D, 0), /**< PD0 */
GPIO_PD1 = GPIO_PXX_TO_NUM(PORT_D, 1), /**< PD1 */
GPIO_PD2 = GPIO_PXX_TO_NUM(PORT_D, 2), /**< PD2 */
GPIO_PD3 = GPIO_PXX_TO_NUM(PORT_D, 3), /**< PD3 */
GPIO_PD4 = GPIO_PXX_TO_NUM(PORT_D, 4), /**< PD4 */
GPIO_PD5 = GPIO_PXX_TO_NUM(PORT_D, 5), /**< PD5 */
GPIO_PD6 = GPIO_PXX_TO_NUM(PORT_D, 6), /**< PD6 */
GPIO_PD7 = GPIO_PXX_TO_NUM(PORT_D, 7), /**< PD7 */
};
/** @} */
/**
* @brief GPIO port component registers
*/
typedef struct {
cc2538_reg_t RESERVED1[255]; /**< Reserved addresses */
cc2538_reg_t DATA; /**< GPIO_A Data Register */
cc2538_reg_t DIR; /**< GPIO_A data direction register */
cc2538_reg_t IS; /**< GPIO_A Interrupt Sense register */
cc2538_reg_t IBE; /**< GPIO_A Interrupt Both-Edges register */
cc2538_reg_t IEV; /**< GPIO_A Interrupt Event Register */
cc2538_reg_t IE; /**< GPIO_A Interrupt mask register */
cc2538_reg_t RIS; /**< GPIO_A Raw Interrupt Status register */
cc2538_reg_t MIS; /**< GPIO_A Masked Interrupt Status register */
cc2538_reg_t IC; /**< GPIO_A Interrupt Clear register */
cc2538_reg_t AFSEL; /**< GPIO_A Alternate Function / mode control select register */
cc2538_reg_t RESERVED2[63]; /**< Reserved addresses */
cc2538_reg_t GPIOLOCK; /**< GPIO_A Lock register */
cc2538_reg_t GPIOCR; /**< GPIO_A Commit Register */
cc2538_reg_t RESERVED3[118]; /**< Reserved addresses */
cc2538_reg_t PMUX; /**< GPIO_A The PMUX register */
cc2538_reg_t P_EDGE_CTRL; /**< GPIO_A The Port Edge Control register */
cc2538_reg_t RESERVED4[2]; /**< Reserved addresses */
cc2538_reg_t PI_IEN; /**< GPIO_A The Power-up Interrupt Enable register */
cc2538_reg_t RESERVED5[1]; /**< Reserved addresses */
cc2538_reg_t IRQ_DETECT_ACK; /**< GPIO_A IRQ Detect ACK register */
cc2538_reg_t USB_IRQ_ACK; /**< GPIO_A IRQ Detect ACK for USB */
cc2538_reg_t IRQ_DETECT_UNMASK; /**< GPIO_A IRQ Detect ACK for masked interrupts */
cc2538_reg_t RESERVED6[567]; /**< Reserved addresses */
} cc2538_gpio_t;
#define GPIO_A ( (cc2538_gpio_t*)0x400d9000 ) /**< GPIO Port A instance */
#define GPIO_B ( (cc2538_gpio_t*)0x400da000 ) /**< GPIO Port B instance */
#define GPIO_C ( (cc2538_gpio_t*)0x400db000 ) /**< GPIO Port C instance */
#define GPIO_D ( (cc2538_gpio_t*)0x400dc000 ) /**< GPIO Port D instance */
void gpio_port_a_isr(void); /**< Interrupt service routine for Port A */
void gpio_port_b_isr(void); /**< Interrupt service routine for Port B */
void gpio_port_c_isr(void); /**< Interrupt service routine for Port C */
void gpio_port_d_isr(void); /**< Interrupt service routine for Port D */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* CC2538_GPIO_H */
/** @} */
/** @} */

@ -0,0 +1,168 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup cpu_cc2538
* @{
*
* @file cc2538-uart.h
* @brief CC2538 UART interface
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef CC2538_UART_H
#define CC2538_UART_H
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief UART component registers
*/
typedef struct {
cc2538_reg_t DR; /**< UART Data Register */
union {
cc2538_reg_t RSR; /**< UART receive status and error clear */
cc2538_reg_t ECR; /**< UART receive status and error clear */
};
cc2538_reg_t RESERVED1[4]; /**< Reserved addresses */
union {
cc2538_reg_t FR; /**< UART Flag Register */
struct {
cc2538_reg_t CTS : 1; /**< Clear to send (UART1 only) */
cc2538_reg_t RESERVED2 : 2; /**< Reserved bits */
cc2538_reg_t BUSY : 1; /**< UART busy */
cc2538_reg_t RXFE : 1; /**< UART receive FIFO empty */
cc2538_reg_t TXFF : 1; /**< UART transmit FIFO full */
cc2538_reg_t RXFF : 1; /**< UART receive FIFO full */
cc2538_reg_t TXFE : 1; /**< UART transmit FIFO empty */
cc2538_reg_t RESERVED1 : 24; /**< Reserved bits */
} FRbits;
};
cc2538_reg_t RESERVED2; /**< Reserved byte */
cc2538_reg_t ILPR; /**< UART IrDA Low-Power Register */
cc2538_reg_t IBRD; /**< UART Integer Baud-Rate Divisor */
cc2538_reg_t FBRD; /**< UART Fractional Baud-Rate Divisor */
union {
cc2538_reg_t LCRH; /**< UART Line Control Register */
struct {
cc2538_reg_t BRK : 1; /**< UART send break */
cc2538_reg_t PEN : 1; /**< UART parity enable */
cc2538_reg_t EPS : 1; /**< UART even parity select */
cc2538_reg_t STP2 : 1; /**< UART two stop bits select */
cc2538_reg_t FEN : 1; /**< UART enable FIFOs */
cc2538_reg_t WLEN : 2; /**< UART word length */
cc2538_reg_t SPS : 1; /**< UART stick parity select */
cc2538_reg_t RESERVED : 24; /**< Reserved bits */
} LCRHbits;
};
union {
cc2538_reg_t CTL; /**< UART Control */
struct {
cc2538_reg_t UARTEN : 1; /**< UART enable */
cc2538_reg_t SIREN : 1; /**< UART SIR enable */
cc2538_reg_t SIRLP : 1; /**< UART SIR low-power mode */
cc2538_reg_t RESERVED11 : 1; /**< Reserved bits */
cc2538_reg_t EOT : 1; /**< End of transmission */
cc2538_reg_t HSE : 1; /**< High-speed enable */
cc2538_reg_t LIN : 1; /**< LIN mode enable */
cc2538_reg_t LBE : 1; /**< UART loop back enable */
cc2538_reg_t TXE : 1; /**< UART transmit enable */
cc2538_reg_t RXE : 1; /**< UART receive enable */
cc2538_reg_t RESERVED12 : 4; /**< Reserved bits */
cc2538_reg_t RTSEN : 1; /**< U1RTS Hardware flow control enable */
cc2538_reg_t CTSEN : 1; /**< U1CTS Hardware flow control enable */
cc2538_reg_t RESERVED13 : 16; /**< Reserved bits */
} CTLbits;
};
union {
cc2538_reg_t IFLS; /**< UART interrupt FIFO Level Select */
struct {
cc2538_reg_t TXIFLSEL : 3; /**< UART transmit interrupt FIFO level select */
cc2538_reg_t RXIFLSEL : 3; /**< UART receive interrupt FIFO level select */
cc2538_reg_t RESERVED : 26; /**< Reserved bits */
} IFLSbits;
};
union {
cc2538_reg_t IM; /**< UART Interrupt Mask */
struct {
cc2538_reg_t RESERVED3 : 4; /**< Reserved bits */
cc2538_reg_t RXIM : 1; /**< UART receive interrupt mask */
cc2538_reg_t TXIM : 1; /**< UART transmit interrupt mask */
cc2538_reg_t RTIM : 1; /**< UART receive time-out interrupt mask */
cc2538_reg_t FEIM : 1; /**< UART framing error interrupt mask */
cc2538_reg_t PEIM : 1; /**< UART parity error interrupt mask */
cc2538_reg_t BEIM : 1; /**< UART break error interrupt mask */
cc2538_reg_t OEIM : 1; /**< UART overrun error interrupt mask */
cc2538_reg_t RESERVED2 : 1; /**< Reserved bits */
cc2538_reg_t NINEBITM : 1; /**< 9-bit mode interrupt mask */
cc2538_reg_t LMSBIM : 1; /**< LIN mode sync break interrupt mask */
cc2538_reg_t LME1IM : 1; /**< LIN mode edge 1 interrupt mask */
cc2538_reg_t LME5IM : 1; /**< LIN mode edge 5 interrupt mask */
cc2538_reg_t RESERVED1 : 16; /**< Reserved bits */
} IMbits;
};
cc2538_reg_t RIS; /**< UART Raw Interrupt Status */
union {
cc2538_reg_t MIS; /**< UART Masked Interrupt Status */
struct {
cc2538_reg_t RESERVED8 : 4; /**< Reserved bits */
cc2538_reg_t RXMIS : 1; /**< UART receive masked interrupt status */
cc2538_reg_t TXMIS : 1; /**< UART transmit masked interrupt status */
cc2538_reg_t RTMIS : 1; /**< UART receive time-out masked interrupt status */
cc2538_reg_t FEMIS : 1; /**< UART framing error masked interrupt status */
cc2538_reg_t PEMIS : 1; /**< UART parity error masked interrupt status */
cc2538_reg_t BEMIS : 1; /**< UART break error masked interrupt status */
cc2538_reg_t OEMIS : 1; /**< UART overrun error masked interrupt status */
cc2538_reg_t RESERVED9 : 1; /**< Reserved bits */
cc2538_reg_t NINEBITMIS : 1; /**< 9-bit mode masked interrupt status */
cc2538_reg_t LMSBMIS : 1; /**< LIN mode sync break masked interrupt status */
cc2538_reg_t LME1MIS : 1; /**< LIN mode edge 1 masked interrupt status */
cc2538_reg_t LME5MIS : 1; /**< LIN mode edge 5 masked interrupt status */
cc2538_reg_t RESERVED10 : 16; /**< Reserved bits */
} MISbits;
};
cc2538_reg_t ICR; /**< UART Interrupt Clear Register */
cc2538_reg_t DMACTL; /**< UART DMA Control */
cc2538_reg_t RESERVED3[17]; /**< Reserved addresses */
cc2538_reg_t LCTL; /**< UART LIN Control */
cc2538_reg_t LSS; /**< UART LIN Snap Shot */
cc2538_reg_t LTIM; /**< UART LIN Timer */
cc2538_reg_t RESERVED4[2]; /**< Reserved addresses */
cc2538_reg_t NINEBITADDR; /**< UART 9-bit self Address */
cc2538_reg_t NINEBITAMASK; /**< UART 9-bit self Address Mask */
cc2538_reg_t RESERVED5[965]; /**< Reserved addresses */
cc2538_reg_t PP; /**< UART Peripheral Properties */
cc2538_reg_t RESERVED6; /**< Reserved addresses */
cc2538_reg_t CC; /**< UART Clock Configuration */
cc2538_reg_t RESERVED7[13]; /**< Reserved addresses */
} cc2538_uart_t;
extern cc2538_uart_t * const UART0; /**< UART0 Instance */
extern cc2538_uart_t * const UART1; /**< UART1 Instance */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* CC2538_UART_H */

@ -0,0 +1,818 @@
/*
* Copyright (C) 2014 Loci Controls Inc.
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @addtogroup cpu_cc2538_definitions
* @{
*
* @file cc2538.h
* @brief CC2538 MCU interrupt and register definitions
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef _CC2538_
#define _CC2538_
#ifdef __cplusplus
extern "C" {
#endif
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR CC2538 */
/* ************************************************************************** */
/** @addtogroup CC2538_cmsis CMSIS Definitions */
/*@{*/
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** Cortex-M3 Processor Exceptions Numbers ****************************/
ResetHandler_IRQn = -15, /**< 1 Reset Handler */
NonMaskableInt_IRQn = -14, /**< 2 Non Maskable Interrupt */
HardFault_IRQn = -13, /**< 3 Cortex-M3 Hard Fault Interrupt */
MemoryManagement_IRQn = -12, /**< 4 Cortex-M3 Memory Management Interrupt */
BusFault_IRQn = -11, /**< 5 Cortex-M3 Bus Fault Interrupt */
UsageFault_IRQn = -10, /**< 6 Cortex-M3 Usage Fault Interrupt */
SVCall_IRQn = - 5, /**< 11 Cortex-M3 SV Call Interrupt */
DebugMonitor_IRQn = - 4, /**< 12 Cortex-M3 Debug Monitor Interrupt */
PendSV_IRQn = - 2, /**< 14 Cortex-M3 Pend SV Interrupt */
SysTick_IRQn = - 1, /**< 15 Cortex-M3 System Tick Interrupt */
/****** CC2538 specific Interrupt Numbers *********************************/
GPIO_PORT_A_IRQn = 0, /**< GPIO port A */
GPIO_PORT_B_IRQn = 1, /**< GPIO port B */
GPIO_PORT_C_IRQn = 2, /**< GPIO port C */
GPIO_PORT_D_IRQn = 3, /**< GPIO port D */
UART0_IRQn = 5, /**< UART0 */
UART1_IRQn = 6, /**< UART1 */
SSI0_IRQn = 7, /**< SSI0 */
I2C_IRQn = 8, /**< I2C */
ADC_IRQn = 14, /**< ADC */
WDT_IRQn = 18, /**< Watchdog Timer */
GPTIMER_0A_IRQn = 19, /**< GPTimer 0A */
GPTIMER_0B_IRQn = 20, /**< GPTimer 0B */
GPTIMER_1A_IRQn = 21, /**< GPTimer 1A */
GPTIMER_1B_IRQn = 22, /**< GPTimer 1B */
GPTIMER_2A_IRQn = 23, /**< GPTimer 2A */
GPTIMER_2B_IRQn = 24, /**< GPTimer 2B */
ADC_CMP_IRQn = 25, /**< Analog Comparator */
RF_RXTX_ALT_IRQn = 26, /**< RF TX/RX (Alternate) */
RF_ERR_ALT_IRQn = 27, /**< RF Error (Alternate) */
SYS_CTRL_IRQn = 28, /**< System Control */
FLASH_CTRL_IRQn = 29, /**< Flash memory control */
AES_ALT_IRQn = 30, /**< AES (Alternate) */
PKA_ALT_IRQn = 31, /**< PKA (Alternate) */
SM_TIMER_ALT_IRQn = 32, /**< SM Timer (Alternate) */
MAC_TIMER_ALT_IRQn = 33, /**< MAC Timer (Alternate) */
SSI1_IRQn = 34, /**< SSI1 */
GPTIMER_3A_IRQn = 35, /**< GPTimer 3A */
GPTIMER_3B_IRQn = 36, /**< GPTimer 3B */
UDMA_IRQn = 46, /**< uDMA software */
UDMA_ERR_IRQn = 47, /**< uDMA error */
USB_IRQn = 140, /**< USB */
RF_RXTX_IRQn = 141, /**< RF Core Rx/Tx */
RF_ERR_IRQn = 142, /**< RF Core Error */
AES_IRQn = 143, /**< AES */
PKA_IRQn = 144, /**< PKA */
SM_TIMER_IRQn = 145, /**< SM Timer */
MACTIMER_IRQn = 146, /**< MAC Timer */
PERIPH_COUNT_IRQn = (MACTIMER_IRQn + 1) /**< Number of peripheral IDs */
} IRQn_Type;
/** @name Cortex-M3 core interrupt handlers
* @{
*/
void Reset_Handler(void); /**< Reset handler */
void NMI_Handler(void); /**< NMI handler */
void HardFault_Handler(void); /**< Hard fault handler */
void MemManage_Handler(void); /**< Memory management handler */
void BusFault_Handler(void); /**< Bus fault handler */
void UsageFault_Handler(void); /**< Usage fault handler */
void SVC_Handler(void); /**< SVC handler */
void DebugMon_Handler(void); /**< Debug monitor handler */
void PendSV_Handler(void); /**< PendSV handler */
void SysTick_Handler(void); /**< SysTick handler */
/* @} */
/**
* @brief Configuration of the Cortex-M3 Processor and Core Peripherals
*/
#define __CM3_REV 0x0200 /**< CC2538 core revision number ([15:8] revision number, [7:0] patch number) */
#define __MPU_PRESENT 1 /**< CC2538 does provide a MPU */
#define __NVIC_PRIO_BITS 4 /**< CC2538 uses 4 Bits for the Priority Levels */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
/**
* @brief CMSIS includes
*/
#include <core_cm3.h>
/*@}*/
#define IEEE_ADDR_MSWORD ( *(const uint32_t*)0x00280028 ) /**< Most-significant 32 bits of the IEEE address */
#define IEEE_ADDR_LSWORD ( *(const uint32_t*)0x0028002c ) /**< Least-significant 32 bits of the IEEE address */
typedef volatile uint32_t cc2538_reg_t; /**< Least-significant 32 bits of the IEEE address */
/** @addtogroup Peripheral_memory_map
* @{
*/
#define FLASH_BASE 0x00200000 /**< FLASH base address */
#define SRAM_BASE 0x20000000 /**< SRAM base address */
#define PERIPH_BASE 0x40000000 /**< Peripheral base address */
#define SRAM_BB_BASE 0x22000000 /**< SRAM base address in the bit-band region */
/** @} */
/** @name CC2538 Special Function Registers
* @{
*/
#define SSI0_CR0 ( *(cc2538_reg_t*)0x40008000 ) /**< SSI0 Control Register 0 */
#define SSI0_CR1 ( *(cc2538_reg_t*)0x40008004 ) /**< SSI0 Control Register 1 */
#define SSI0_DR ( *(cc2538_reg_t*)0x40008008 ) /**< SSI0 Data register */
#define SSI0_SR ( *(cc2538_reg_t*)0x4000800c ) /**< SSI0 FIFO/busy Status Register */
#define SSI0_CPSR ( *(cc2538_reg_t*)0x40008010 ) /**< SSI0 Clock Register */
#define SSI0_IM ( *(cc2538_reg_t*)0x40008014 ) /**< SSI0 Interrupt Mask register */
#define SSI0_RIS ( *(cc2538_reg_t*)0x40008018 ) /**< SSI0 Raw Interrupt Status register */
#define SSI0_MIS ( *(cc2538_reg_t*)0x4000801c ) /**< SSI0 Masked Interrupt Status register */
#define SSI0_ICR ( *(cc2538_reg_t*)0x40008020 ) /**< SSI0 Interrupt Clear Register */
#define SSI0_DMACTL ( *(cc2538_reg_t*)0x40008024 ) /**< SSI0 uDMA Control Register. */
#define SSI0_CC ( *(cc2538_reg_t*)0x40008fc8 ) /**< SSI0 clock configuration */
#define SSI1_CR0 ( *(cc2538_reg_t*)0x40009000 ) /**< SSI1 Control Register 0 */
#define SSI1_CR1 ( *(cc2538_reg_t*)0x40009004 ) /**< SSI1 Control Register 1 */
#define SSI1_DR ( *(cc2538_reg_t*)0x40009008 ) /**< SSI1 Data register */
#define SSI1_SR ( *(cc2538_reg_t*)0x4000900c ) /**< SSI1 FIFO/busy Status Register */
#define SSI1_CPSR ( *(cc2538_reg_t*)0x40009010 ) /**< SSI1 Clock Register */
#define SSI1_IM ( *(cc2538_reg_t*)0x40009014 ) /**< SSI1 Interrupt Mask register */
#define SSI1_RIS ( *(cc2538_reg_t*)0x40009018 ) /**< SSI1 Raw Interrupt Status register */
#define SSI1_MIS ( *(cc2538_reg_t*)0x4000901c ) /**< SSI1 Masked Interrupt Status register */
#define SSI1_ICR ( *(cc2538_reg_t*)0x40009020 ) /**< SSI1 Interrupt Clear Register */
#define SSI1_DMACTL ( *(cc2538_reg_t*)0x40009024 ) /**< SSI1 uDMA Control Register. */
#define SSI1_CC ( *(cc2538_reg_t*)0x40009fc8 ) /**< SSI1 clock configuration */
#define UART0_DR ( *(cc2538_reg_t*)0x4000c000 ) /**< UART0 Data Register */
#define UART0_ECR ( *(cc2538_reg_t*)0x4000c004 ) /**< UART0 receive status and error clear */
#define UART0_RSR ( *(cc2538_reg_t*)0x4000c004 ) /**< UART0 receive status and error clear */
#define UART0_FR ( *(cc2538_reg_t*)0x4000c018 ) /**< UART0 flag */
#define UART0_ILPR ( *(cc2538_reg_t*)0x4000c020 ) /**< UART0 IrDA low-power register */
#define UART0_IBRD ( *(cc2538_reg_t*)0x4000c024 ) /**< UART0 integer baud-rate divisor */
#define UART0_FBRD ( *(cc2538_reg_t*)0x4000c028 ) /**< UART0 fractional baud-rate divisor */
#define UART0_LCRH ( *(cc2538_reg_t*)0x4000c02c ) /**< UART0 line control */
#define UART0_CTL ( *(cc2538_reg_t*)0x4000c030 ) /**< UART0 control */
#define UART0_IFLS ( *(cc2538_reg_t*)0x4000c034 ) /**< UART0 interrupt FIFO level select */
#define UART0_IM ( *(cc2538_reg_t*)0x4000c038 ) /**< UART0 interrupt mask */
#define UART0_RIS ( *(cc2538_reg_t*)0x4000c03c ) /**< UART0 raw interrupt status */
#define UART0_MIS ( *(cc2538_reg_t*)0x4000c040 ) /**< UART0 masked interrupt status */
#define UART0_ICR ( *(cc2538_reg_t*)0x4000c044 ) /**< UART0 interrupt clear */
#define UART0_DMACTL ( *(cc2538_reg_t*)0x4000c048 ) /**< UART0 DMA control */
#define UART0_LCTL ( *(cc2538_reg_t*)0x4000c090 ) /**< UART0 LIN control */
#define UART0_LSS ( *(cc2538_reg_t*)0x4000c094 ) /**< UART0 LIN snap shot */
#define UART0_LTIM ( *(cc2538_reg_t*)0x4000c098 ) /**< UART0 LIN timer */
#define UART0_NINEBITADDR ( *(cc2538_reg_t*)0x4000c0a4 ) /**< UART0 9-bit self address */
#define UART0_NINEBITAMASK ( *(cc2538_reg_t*)0x4000c0a8 ) /**< UART0 9-bit self address mask */
#define UART0_PP ( *(cc2538_reg_t*)0x4000cfc0 ) /**< UART0 peripheral properties */
#define UART0_CC ( *(cc2538_reg_t*)0x4000cfc8 ) /**< UART0 clock configuration */
#define UART1_DR ( *(cc2538_reg_t*)0x4000d000 ) /**< UART1 Data Register */
#define UART1_ECR ( *(cc2538_reg_t*)0x4000d004 ) /**< UART1 receive status and error clear */
#define UART1_RSR ( *(cc2538_reg_t*)0x4000d004 ) /**< UART1 receive status and error clear */
#define UART1_FR ( *(cc2538_reg_t*)0x4000d018 ) /**< UART1 flag */
#define UART1_ILPR ( *(cc2538_reg_t*)0x4000d020 ) /**< UART1 IrDA low-power register */
#define UART1_IBRD ( *(cc2538_reg_t*)0x4000d024 ) /**< UART1 integer baud-rate divisor */
#define UART1_FBRD ( *(cc2538_reg_t*)0x4000d028 ) /**< UART1 fractional baud-rate divisor */
#define UART1_LCRH ( *(cc2538_reg_t*)0x4000d02c ) /**< UART1 line control */
#define UART1_CTL ( *(cc2538_reg_t*)0x4000d030 ) /**< UART1 control */
#define UART1_IFLS ( *(cc2538_reg_t*)0x4000d034 ) /**< UART1 interrupt FIFO level select */
#define UART1_IM ( *(cc2538_reg_t*)0x4000d038 ) /**< UART1 interrupt mask */
#define UART1_RIS ( *(cc2538_reg_t*)0x4000d03c ) /**< UART1 raw interrupt status */
#define UART1_MIS ( *(cc2538_reg_t*)0x4000d040 ) /**< UART1 masked interrupt status */
#define UART1_ICR ( *(cc2538_reg_t*)0x4000d044 ) /**< UART1 interrupt clear */
#define UART1_DMACTL ( *(cc2538_reg_t*)0x4000d048 ) /**< UART1 DMA control */
#define UART1_LCTL ( *(cc2538_reg_t*)0x4000d090 ) /**< UART1 LIN control */
#define UART1_LSS ( *(cc2538_reg_t*)0x4000d094 ) /**< UART1 LIN snap shot */
#define UART1_LTIM ( *(cc2538_reg_t*)0x4000d098 ) /**< UART1 LIN timer */
#define UART1_NINEBITADDR ( *(cc2538_reg_t*)0x4000d0a4 ) /**< UART1 9-bit self address */
#define UART1_NINEBITAMASK ( *(cc2538_reg_t*)0x4000d0a8 ) /**< UART1 9-bit self address mask */
#define UART1_PP ( *(cc2538_reg_t*)0x4000dfc0 ) /**< UART1 peripheral properties */
#define UART1_CC ( *(cc2538_reg_t*)0x4000dfc8 ) /**< UART1 clock configuration */
#define I2CM_SA ( *(cc2538_reg_t*)0x40020000 ) /**< I2C Master Slave address */
#define I2CM_CTRL ( *(cc2538_reg_t*)0x40020004 ) /**< I2C Master Control and status */
#define I2CM_STAT ( *(cc2538_reg_t*)0x40020004 ) /**< I2C Master Control and status */
#define I2CM_DR ( *(cc2538_reg_t*)0x40020008 ) /**< I2C Master Data */
#define I2CM_TPR ( *(cc2538_reg_t*)0x4002000c ) /**< I2C Master Timer period */
#define I2CM_IMR ( *(cc2538_reg_t*)0x40020010 ) /**< I2C Master Interrupt mask */
#define I2CM_RIS ( *(cc2538_reg_t*)0x40020014 ) /**< I2C Master Raw interrupt status */
#define I2CM_MIS ( *(cc2538_reg_t*)0x40020018 ) /**< I2C Master Masked interrupt status */
#define I2CM_ICR ( *(cc2538_reg_t*)0x4002001c ) /**< I2C Master Interrupt clear */
#define I2CM_CR ( *(cc2538_reg_t*)0x40020020 ) /**< I2C Master Configuration */
#define I2CS_OAR ( *(cc2538_reg_t*)0x40020800 ) /**< I2C Slave own address */
#define I2CS_CTRL ( *(cc2538_reg_t*)0x40020804 ) /**< I2C Slave Control and status */
#define I2CS_STAT ( *(cc2538_reg_t*)0x40020804 ) /**< I2C Slave Control and status */
#define I2CS_DR ( *(cc2538_reg_t*)0x40020808 ) /**< I2C Slave Data */
#define I2CS_IMR ( *(cc2538_reg_t*)0x4002080c ) /**< I2C Slave Interrupt mask */
#define I2CS_RIS ( *(cc2538_reg_t*)0x40020810 ) /**< I2C Slave Raw interrupt status */
#define I2CS_MIS ( *(cc2538_reg_t*)0x40020814 ) /**< I2C Slave Masked interrupt status */
#define I2CS_ICR ( *(cc2538_reg_t*)0x40020818 ) /**< I2C Slave Interrupt clear */
#define GPTIMER0_CFG ( *(cc2538_reg_t*)0x40030000 ) /**< GPTM0 configuration */
#define GPTIMER0_TAMR ( *(cc2538_reg_t*)0x40030004 ) /**< GPTM0 Timer A mode */
#define GPTIMER0_TBMR ( *(cc2538_reg_t*)0x40030008 ) /**< GPTM0 Timer B mode */
#define GPTIMER0_CTL ( *(cc2538_reg_t*)0x4003000c ) /**< GPTM0 control */
#define GPTIMER0_SYNC ( *(cc2538_reg_t*)0x40030010 ) /**< GPTM0 synchronize */
#define GPTIMER0_IMR ( *(cc2538_reg_t*)0x40030018 ) /**< GPTM0 interrupt mask */
#define GPTIMER0_RIS ( *(cc2538_reg_t*)0x4003001c ) /**< GPTM0 raw interrupt status */
#define GPTIMER0_MIS ( *(cc2538_reg_t*)0x40030020 ) /**< GPTM0 masked interrupt status */
#define GPTIMER0_ICR ( *(cc2538_reg_t*)0x40030024 ) /**< GPTM0 interrupt clear */
#define GPTIMER0_TAILR ( *(cc2538_reg_t*)0x40030028 ) /**< GPTM0 Timer A interval load */
#define GPTIMER0_TBILR ( *(cc2538_reg_t*)0x4003002c ) /**< GPTM0 Timer B interval load */
#define GPTIMER0_TAMATCHR ( *(cc2538_reg_t*)0x40030030 ) /**< GPTM0 Timer A match */
#define GPTIMER0_TBMATCHR ( *(cc2538_reg_t*)0x40030034 ) /**< GPTM0 Timer B match */
#define GPTIMER0_TAPR ( *(cc2538_reg_t*)0x40030038 ) /**< GPTM0 Timer A prescale */
#define GPTIMER0_TBPR ( *(cc2538_reg_t*)0x4003003c ) /**< GPTM0 Timer B prescale */
#define GPTIMER0_TAPMR ( *(cc2538_reg_t*)0x40030040 ) /**< GPTM0 Timer A prescale match */
#define GPTIMER0_TBPMR ( *(cc2538_reg_t*)0x40030044 ) /**< GPTM0 Timer B prescale match */
#define GPTIMER0_TAR ( *(cc2538_reg_t*)0x40030048 ) /**< GPTM0 Timer A */
#define GPTIMER0_TBR ( *(cc2538_reg_t*)0x4003004c ) /**< GPTM0 Timer B */
#define GPTIMER0_TAV ( *(cc2538_reg_t*)0x40030050 ) /**< GPTM0 Timer A value */
#define GPTIMER0_TBV ( *(cc2538_reg_t*)0x40030054 ) /**< GPTM0 Timer B value */
#define GPTIMER0_TAPS ( *(cc2538_reg_t*)0x4003005c ) /**< GPTM0 Timer A prescale snapshot */
#define GPTIMER0_TBPS ( *(cc2538_reg_t*)0x40030060 ) /**< GPTM0 Timer B prescale snapshot */
#define GPTIMER0_TAPV ( *(cc2538_reg_t*)0x40030064 ) /**< GPTM0 Timer A prescale value */
#define GPTIMER0_TBPV ( *(cc2538_reg_t*)0x40030068 ) /**< GPTM0 Timer B prescale value */
#define GPTIMER0_PP ( *(cc2538_reg_t*)0x40030fc0 ) /**< GPTM0 peripheral properties */
#define GPTIMER1_CFG ( *(cc2538_reg_t*)0x40031000 ) /**< GPTM1 configuration */
#define GPTIMER1_TAMR ( *(cc2538_reg_t*)0x40031004 ) /**< GPTM1 Timer A mode */
#define GPTIMER1_TBMR ( *(cc2538_reg_t*)0x40031008 ) /**< GPTM1 Timer B mode */
#define GPTIMER1_CTL ( *(cc2538_reg_t*)0x4003100c ) /**< GPTM1 control */
#define GPTIMER1_SYNC ( *(cc2538_reg_t*)0x40031010 ) /**< GPTM1 synchronize */
#define GPTIMER1_IMR ( *(cc2538_reg_t*)0x40031018 ) /**< GPTM1 interrupt mask */
#define GPTIMER1_RIS ( *(cc2538_reg_t*)0x4003101c ) /**< GPTM1 raw interrupt status */
#define GPTIMER1_MIS ( *(cc2538_reg_t*)0x40031020 ) /**< GPTM1 masked interrupt status */
#define GPTIMER1_ICR ( *(cc2538_reg_t*)0x40031024 ) /**< GPTM1 interrupt clear */
#define GPTIMER1_TAILR ( *(cc2538_reg_t*)0x40031028 ) /**< GPTM1 Timer A interval load */
#define GPTIMER1_TBILR ( *(cc2538_reg_t*)0x4003102c ) /**< GPTM1 Timer B interval load */
#define GPTIMER1_TAMATCHR ( *(cc2538_reg_t*)0x40031030 ) /**< GPTM1 Timer A match */
#define GPTIMER1_TBMATCHR ( *(cc2538_reg_t*)0x40031034 ) /**< GPTM1 Timer B match */
#define GPTIMER1_TAPR ( *(cc2538_reg_t*)0x40031038 ) /**< GPTM1 Timer A prescale */
#define GPTIMER1_TBPR ( *(cc2538_reg_t*)0x4003103c ) /**< GPTM1 Timer B prescale */
#define GPTIMER1_TAPMR ( *(cc2538_reg_t*)0x40031040 ) /**< GPTM1 Timer A prescale match */
#define GPTIMER1_TBPMR ( *(cc2538_reg_t*)0x40031044 ) /**< GPTM1 Timer B prescale match */
#define GPTIMER1_TAR ( *(cc2538_reg_t*)0x40031048 ) /**< GPTM1 Timer A */
#define GPTIMER1_TBR ( *(cc2538_reg_t*)0x4003104c ) /**< GPTM1 Timer B */
#define GPTIMER1_TAV ( *(cc2538_reg_t*)0x40031050 ) /**< GPTM1 Timer A value */
#define GPTIMER1_TBV ( *(cc2538_reg_t*)0x40031054 ) /**< GPTM1 Timer B value */
#define GPTIMER1_TAPS ( *(cc2538_reg_t*)0x4003105c ) /**< GPTM1 Timer A prescale snapshot */
#define GPTIMER1_TBPS ( *(cc2538_reg_t*)0x40031060 ) /**< GPTM1 Timer B prescale snapshot */
#define GPTIMER1_TAPV ( *(cc2538_reg_t*)0x40031064 ) /**< GPTM1 Timer A prescale value */
#define GPTIMER1_TBPV ( *(cc2538_reg_t*)0x40031068 ) /**< GPTM1 Timer B prescale value */
#define GPTIMER1_PP ( *(cc2538_reg_t*)0x40031fc0 ) /**< GPTM1 peripheral properties */
#define GPTIMER2_CFG ( *(cc2538_reg_t*)0x40032000 ) /**< GPTM2 configuration */
#define GPTIMER2_TAMR ( *(cc2538_reg_t*)0x40032004 ) /**< GPTM2 Timer A mode */
#define GPTIMER2_TBMR ( *(cc2538_reg_t*)0x40032008 ) /**< GPTM2 Timer B mode */
#define GPTIMER2_CTL ( *(cc2538_reg_t*)0x4003200c ) /**< GPTM2 control */
#define GPTIMER2_SYNC ( *(cc2538_reg_t*)0x40032010 ) /**< GPTM2 synchronize */
#define GPTIMER2_IMR ( *(cc2538_reg_t*)0x40032018 ) /**< GPTM2 interrupt mask */
#define GPTIMER2_RIS ( *(cc2538_reg_t*)0x4003201c ) /**< GPTM2 raw interrupt status */
#define GPTIMER2_MIS ( *(cc2538_reg_t*)0x40032020 ) /**< GPTM2 masked interrupt status */
#define GPTIMER2_ICR ( *(cc2538_reg_t*)0x40032024 ) /**< GPTM2 interrupt clear */
#define GPTIMER2_TAILR ( *(cc2538_reg_t*)0x40032028 ) /**< GPTM2 Timer A interval load */
#define GPTIMER2_TBILR ( *(cc2538_reg_t*)0x4003202c ) /**< GPTM2 Timer B interval load */
#define GPTIMER2_TAMATCHR ( *(cc2538_reg_t*)0x40032030 ) /**< GPTM2 Timer A match */
#define GPTIMER2_TBMATCHR ( *(cc2538_reg_t*)0x40032034 ) /**< GPTM2 Timer B match */
#define GPTIMER2_TAPR ( *(cc2538_reg_t*)0x40032038 ) /**< GPTM2 Timer A prescale */
#define GPTIMER2_TBPR ( *(cc2538_reg_t*)0x4003203c ) /**< GPTM2 Timer B prescale */
#define GPTIMER2_TAPMR ( *(cc2538_reg_t*)0x40032040 ) /**< GPTM2 Timer A prescale match */
#define GPTIMER2_TBPMR ( *(cc2538_reg_t*)0x40032044 ) /**< GPTM2 Timer B prescale match */
#define GPTIMER2_TAR ( *(cc2538_reg_t*)0x40032048 ) /**< GPTM2 Timer A */
#define GPTIMER2_TBR ( *(cc2538_reg_t*)0x4003204c ) /**< GPTM2 Timer B */
#define GPTIMER2_TAV ( *(cc2538_reg_t*)0x40032050 ) /**< GPTM2 Timer A value */
#define GPTIMER2_TBV ( *(cc2538_reg_t*)0x40032054 ) /**< GPTM2 Timer B value */
#define GPTIMER2_TAPS ( *(cc2538_reg_t*)0x4003205c ) /**< GPTM2 Timer A prescale snapshot */
#define GPTIMER2_TBPS ( *(cc2538_reg_t*)0x40032060 ) /**< GPTM2 Timer B prescale snapshot */
#define GPTIMER2_TAPV ( *(cc2538_reg_t*)0x40032064 ) /**< GPTM2 Timer A prescale value */
#define GPTIMER2_TBPV ( *(cc2538_reg_t*)0x40032068 ) /**< GPTM2 Timer B prescale value */
#define GPTIMER2_PP ( *(cc2538_reg_t*)0x40032fc0 ) /**< GPTM2 peripheral properties */
#define GPTIMER3_CFG ( *(cc2538_reg_t*)0x40033000 ) /**< GPTM3 configuration */
#define GPTIMER3_TAMR ( *(cc2538_reg_t*)0x40033004 ) /**< GPTM3 Timer A mode */
#define GPTIMER3_TBMR ( *(cc2538_reg_t*)0x40033008 ) /**< GPTM3 Timer B mode */
#define GPTIMER3_CTL ( *(cc2538_reg_t*)0x4003300c ) /**< GPTM3 control */
#define GPTIMER3_SYNC ( *(cc2538_reg_t*)0x40033010 ) /**< GPTM3 synchronize */
#define GPTIMER3_IMR ( *(cc2538_reg_t*)0x40033018 ) /**< GPTM3 interrupt mask */
#define GPTIMER3_RIS ( *(cc2538_reg_t*)0x4003301c ) /**< GPTM3 raw interrupt status */
#define GPTIMER3_MIS ( *(cc2538_reg_t*)0x40033020 ) /**< GPTM3 masked interrupt status */
#define GPTIMER3_ICR ( *(cc2538_reg_t*)0x40033024 ) /**< GPTM3 interrupt clear */
#define GPTIMER3_TAILR ( *(cc2538_reg_t*)0x40033028 ) /**< GPTM3 Timer A interval load */
#define GPTIMER3_TBILR ( *(cc2538_reg_t*)0x4003302c ) /**< GPTM3 Timer B interval load */
#define GPTIMER3_TAMATCHR ( *(cc2538_reg_t*)0x40033030 ) /**< GPTM3 Timer A match */
#define GPTIMER3_TBMATCHR ( *(cc2538_reg_t*)0x40033034 ) /**< GPTM3 Timer B match */
#define GPTIMER3_TAPR ( *(cc2538_reg_t*)0x40033038 ) /**< GPTM3 Timer A prescale */
#define GPTIMER3_TBPR ( *(cc2538_reg_t*)0x4003303c ) /**< GPTM3 Timer B prescale */
#define GPTIMER3_TAPMR ( *(cc2538_reg_t*)0x40033040 ) /**< GPTM3 Timer A prescale match */
#define GPTIMER3_TBPMR ( *(cc2538_reg_t*)0x40033044 ) /**< GPTM3 Timer B prescale match */
#define GPTIMER3_TAR ( *(cc2538_reg_t*)0x40033048 ) /**< GPTM3 Timer A */
#define GPTIMER3_TBR ( *(cc2538_reg_t*)0x4003304c ) /**< GPTM3 Timer B */
#define GPTIMER3_TAV ( *(cc2538_reg_t*)0x40033050 ) /**< GPTM3 Timer A value */
#define GPTIMER3_TBV ( *(cc2538_reg_t*)0x40033054 ) /**< GPTM3 Timer B value */
#define GPTIMER3_TAPS ( *(cc2538_reg_t*)0x4003305c ) /**< GPTM3 Timer A prescale snapshot */
#define GPTIMER3_TBPS ( *(cc2538_reg_t*)0x40033060 ) /**< GPTM3 Timer B prescale snapshot */
#define GPTIMER3_TAPV ( *(cc2538_reg_t*)0x40033064 ) /**< GPTM3 Timer A prescale value */
#define GPTIMER3_TBPV ( *(cc2538_reg_t*)0x40033068 ) /**< GPTM3 Timer B prescale value */
#define GPTIMER3_PP ( *(cc2538_reg_t*)0x40033fc0 ) /**< GPTM3 peripheral properties */
#define RFCORE_FFSM_SRCRESMASK0 ( *(cc2538_reg_t*)0x40088580 ) /**< RF Source address matching result */
#define RFCORE_FFSM_SRCRESMASK1 ( *(cc2538_reg_t*)0x40088584 ) /**< RF Source address matching result */
#define RFCORE_FFSM_SRCRESMASK2 ( *(cc2538_reg_t*)0x40088588 ) /**< RF Source address matching result */
#define RFCORE_FFSM_SRCRESINDEX ( *(cc2538_reg_t*)0x4008858c ) /**< RF Source address matching result */
#define RFCORE_FFSM_SRCEXTPENDEN0 ( *(cc2538_reg_t*)0x40088590 ) /**< RF Source address matching control */
#define RFCORE_FFSM_SRCEXTPENDEN1 ( *(cc2538_reg_t*)0x40088594 ) /**< RF Source address matching control */
#define RFCORE_FFSM_SRCEXTPENDEN2 ( *(cc2538_reg_t*)0x40088598 ) /**< RF Source address matching control */
#define RFCORE_FFSM_SRCSHORTPENDEN0 ( *(cc2538_reg_t*)0x4008859c ) /**< RF Source address matching control */
#define RFCORE_FFSM_SRCSHORTPENDEN1 ( *(cc2538_reg_t*)0x400885a0 ) /**< RF Source address matching control */
#define RFCORE_FFSM_SRCSHORTPENDEN2 ( *(cc2538_reg_t*)0x400885a4 ) /**< RF Source address matching control */
#define RFCORE_FFSM_EXT_ADDR0 ( *(cc2538_reg_t*)0x400885a8 ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR1 ( *(cc2538_reg_t*)0x400885ac ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR2 ( *(cc2538_reg_t*)0x400885b0 ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR3 ( *(cc2538_reg_t*)0x400885b4 ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR4 ( *(cc2538_reg_t*)0x400885b8 ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR5 ( *(cc2538_reg_t*)0x400885bc ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR6 ( *(cc2538_reg_t*)0x400885c0 ) /**< RF Local address information */
#define RFCORE_FFSM_EXT_ADDR7 ( *(cc2538_reg_t*)0x400885c4 ) /**< RF Local address information */
#define RFCORE_FFSM_PAN_ID0 ( *(cc2538_reg_t*)0x400885c8 ) /**< RF Local address information */
#define RFCORE_FFSM_PAN_ID1 ( *(cc2538_reg_t*)0x400885cc ) /**< RF Local address information */
#define RFCORE_FFSM_SHORT_ADDR0 ( *(cc2538_reg_t*)0x400885d0 ) /**< RF Local address information */
#define RFCORE_FFSM_SHORT_ADDR1 ( *(cc2538_reg_t*)0x400885d4 ) /**< RF Local address information */
#define RFCORE_XREG_FRMFILT0 ( *(cc2538_reg_t*)0x40088600 ) /**< RF Frame Filter 0 */
#define RFCORE_XREG_FRMFILT1 ( *(cc2538_reg_t*)0x40088604 ) /**< RF Frame Filter 1 */
#define RFCORE_XREG_SRCMATCH ( *(cc2538_reg_t*)0x40088608 ) /**< RF Source address matching and pending bits */
#define RFCORE_XREG_SRCSHORTEN0 ( *(cc2538_reg_t*)0x4008860c ) /**< RF Short address matching */
#define RFCORE_XREG_SRCSHORTEN1 ( *(cc2538_reg_t*)0x40088610 ) /**< RF Short address matching */
#define RFCORE_XREG_SRCSHORTEN2 ( *(cc2538_reg_t*)0x40088614 ) /**< RF Short address matching */
#define RFCORE_XREG_SRCEXTEN0 ( *(cc2538_reg_t*)0x40088618 ) /**< RF Extended address matching */
#define RFCORE_XREG_SRCEXTEN1 ( *(cc2538_reg_t*)0x4008861c ) /**< RF Extended address matching */
#define RFCORE_XREG_SRCEXTEN2 ( *(cc2538_reg_t*)0x40088620 ) /**< RF Extended address matching */
#define RFCORE_XREG_FRMCTRL0 ( *(cc2538_reg_t*)0x40088624 ) /**< RF Frame handling */
#define RFCORE_XREG_FRMCTRL1 ( *(cc2538_reg_t*)0x40088628 ) /**< RF Frame handling */
#define RFCORE_XREG_RXENABLE ( *(cc2538_reg_t*)0x4008862c ) /**< RF RX enabling */
#define RFCORE_XREG_RXMASKSET ( *(cc2538_reg_t*)0x40088630 ) /**< RF RX enabling */
#define RFCORE_XREG_RXMASKCLR ( *(cc2538_reg_t*)0x40088634 ) /**< RF RX disabling */
#define RFCORE_XREG_FREQTUNE ( *(cc2538_reg_t*)0x40088638 ) /**< RF Crystal oscillator frequency tuning */
#define RFCORE_XREG_FREQCTRL ( *(cc2538_reg_t*)0x4008863c ) /**< RF Controls the RF frequency */
#define RFCORE_XREG_TXPOWER ( *(cc2538_reg_t*)0x40088640 ) /**< RF Controls the output power */
#define RFCORE_XREG_TXCTRL ( *(cc2538_reg_t*)0x40088644 ) /**< RF Controls the TX settings */
#define RFCORE_XREG_FSMSTAT0 ( *(cc2538_reg_t*)0x40088648 ) /**< RF Radio status register */
#define RFCORE_XREG_FSMSTAT1 ( *(cc2538_reg_t*)0x4008864c ) /**< RF Radio status register */
#define RFCORE_XREG_FIFOPCTRL ( *(cc2538_reg_t*)0x40088650 ) /**< RF FIFOP threshold */
#define RFCORE_XREG_FSMCTRL ( *(cc2538_reg_t*)0x40088654 ) /**< RF FSM options */
#define RFCORE_XREG_CCACTRL0 ( *(cc2538_reg_t*)0x40088658 ) /**< RF CCA threshold */
#define RFCORE_XREG_CCACTRL1 ( *(cc2538_reg_t*)0x4008865c ) /**< RF Other CCA Options */
#define RFCORE_XREG_RSSI ( *(cc2538_reg_t*)0x40088660 ) /**< RF RSSI status register */
#define RFCORE_XREG_RSSISTAT ( *(cc2538_reg_t*)0x40088664 ) /**< RF RSSI valid status register */
#define RFCORE_XREG_RXFIRST ( *(cc2538_reg_t*)0x40088668 ) /**< RF First byte in RX FIFO */
#define RFCORE_XREG_RXFIFOCNT ( *(cc2538_reg_t*)0x4008866c ) /**< RF Number of bytes in RX FIFO */
#define RFCORE_XREG_TXFIFOCNT ( *(cc2538_reg_t*)0x40088670 ) /**< RF Number of bytes in TX FIFO */
#define RFCORE_XREG_RXFIRST_PTR ( *(cc2538_reg_t*)0x40088674 ) /**< RF RX FIFO pointer */
#define RFCORE_XREG_RXLAST_PTR ( *(cc2538_reg_t*)0x40088678 ) /**< RF RX FIFO pointer */
#define RFCORE_XREG_RXP1_PTR ( *(cc2538_reg_t*)0x4008867c ) /**< RF RX FIFO pointer */
#define RFCORE_XREG_TXFIRST_PTR ( *(cc2538_reg_t*)0x40088684 ) /**< RF TX FIFO pointer */
#define RFCORE_XREG_TXLAST_PTR ( *(cc2538_reg_t*)0x40088688 ) /**< RF TX FIFO pointer */
#define RFCORE_XREG_RFIRQM0 ( *(cc2538_reg_t*)0x4008868c ) /**< RF interrupt masks */
#define RFCORE_XREG_RFIRQM1 ( *(cc2538_reg_t*)0x40088690 ) /**< RF interrupt masks */
#define RFCORE_XREG_RFERRM ( *(cc2538_reg_t*)0x40088694 ) /**< RF error interrupt mask */
#define RFCORE_XREG_RFRND ( *(cc2538_reg_t*)0x4008869c ) /**< RF Random data */
#define RFCORE_XREG_MDMCTRL0 ( *(cc2538_reg_t*)0x400886a0 ) /**< RF Controls modem */
#define RFCORE_XREG_MDMCTRL1 ( *(cc2538_reg_t*)0x400886a4 ) /**< RF Controls modem */
#define RFCORE_XREG_FREQEST ( *(cc2538_reg_t*)0x400886a8 ) /**< RF Estimated RF frequency offset */
#define RFCORE_XREG_RXCTRL ( *(cc2538_reg_t*)0x400886ac ) /**< RF Tune receive section */
#define RFCORE_XREG_FSCTRL ( *(cc2538_reg_t*)0x400886b0 ) /**< RF Tune frequency synthesizer */
#define RFCORE_XREG_FSCAL0 ( *(cc2538_reg_t*)0x400886b4 ) /**< RF Tune frequency calibration */
#define RFCORE_XREG_FSCAL1 ( *(cc2538_reg_t*)0x400886b8 ) /**< RF Tune frequency calibration */
#define RFCORE_XREG_FSCAL2 ( *(cc2538_reg_t*)0x400886bc ) /**< RF Tune frequency calibration */
#define RFCORE_XREG_FSCAL3 ( *(cc2538_reg_t*)0x400886c0 ) /**< RF Tune frequency calibration */
#define RFCORE_XREG_AGCCTRL0 ( *(cc2538_reg_t*)0x400886c4 ) /**< RF AGC dynamic range control */
#define RFCORE_XREG_AGCCTRL1 ( *(cc2538_reg_t*)0x400886c8 ) /**< RF AGC reference level */
#define RFCORE_XREG_AGCCTRL2 ( *(cc2538_reg_t*)0x400886cc ) /**< RF AGC gain override */
#define RFCORE_XREG_AGCCTRL3 ( *(cc2538_reg_t*)0x400886d0 ) /**< RF AGC control */
#define RFCORE_XREG_ADCTEST0 ( *(cc2538_reg_t*)0x400886d4 ) /**< RF ADC tuning */
#define RFCORE_XREG_ADCTEST1 ( *(cc2538_reg_t*)0x400886d8 ) /**< RF ADC tuning */
#define RFCORE_XREG_ADCTEST2 ( *(cc2538_reg_t*)0x400886dc ) /**< RF ADC tuning */
#define RFCORE_XREG_MDMTEST0 ( *(cc2538_reg_t*)0x400886e0 ) /**< RF Test register for modem */
#define RFCORE_XREG_MDMTEST1 ( *(cc2538_reg_t*)0x400886e4 ) /**< RF Test Register for Modem */
#define RFCORE_XREG_DACTEST0 ( *(cc2538_reg_t*)0x400886e8 ) /**< RF DAC override value */
#define RFCORE_XREG_DACTEST1 ( *(cc2538_reg_t*)0x400886ec ) /**< RF DAC override value */
#define RFCORE_XREG_DACTEST2 ( *(cc2538_reg_t*)0x400886f0 ) /**< RF DAC test setting */
#define RFCORE_XREG_ATEST ( *(cc2538_reg_t*)0x400886f4 ) /**< RF Analog test control */
#define RFCORE_XREG_PTEST0 ( *(cc2538_reg_t*)0x400886f8 ) /**< RF Override power-down register */
#define RFCORE_XREG_PTEST1 ( *(cc2538_reg_t*)0x400886fc ) /**< RF Override power-down register */
#define RFCORE_XREG_CSPCTRL ( *(cc2538_reg_t*)0x40088780 ) /**< RF CSP control bit */