1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

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

This commit is contained in:
Ian Martin 2014-10-13 09:29:49 -04:00
parent 1258183791
commit 0605a7eb95
37 changed files with 4646 additions and 156 deletions

4
boards/cc2538dk/Makefile Normal file
View File

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

View File

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

View File

@ -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

59
boards/cc2538dk/board.c Normal file
View File

@ -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();
}
/** @} */

View File

@ -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 */
/** @} */

View File

@ -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 */
/** @} */

7
cpu/cc2538/Makefile Normal file
View File

@ -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

View File

@ -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) $< > $@

View File

@ -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
}

View File

@ -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
/* @} */

View File

@ -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
/* @} */

View File

@ -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
/* @} */

90
cpu/cc2538/cpu.c Normal file
View File

@ -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
}

10
cpu/cc2538/doc.txt Normal file
View File

@ -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
*/

View File

@ -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();
}

View File

@ -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 */
/** @} */
/** @} */

View File

@ -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 */

818
cpu/cc2538/include/cc2538.h Normal file
View File

@ -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 */
#define RFCORE_XREG_CSPSTAT ( *(cc2538_reg_t*)0x40088784 ) /**< RF CSP status register */
#define RFCORE_XREG_CSPX ( *(cc2538_reg_t*)0x40088788 ) /**< RF CSP X data register */
#define RFCORE_XREG_CSPY ( *(cc2538_reg_t*)0x4008878c ) /**< RF CSP Y data register */
#define RFCORE_XREG_CSPZ ( *(cc2538_reg_t*)0x40088790 ) /**< RF CSP Z data register */
#define RFCORE_XREG_CSPT ( *(cc2538_reg_t*)0x40088794 ) /**< RF CSP T data register */
#define RFCORE_XREG_RFC_OBS_CTRL0 ( *(cc2538_reg_t*)0x400887ac ) /**< RF observation mux control */
#define RFCORE_XREG_RFC_OBS_CTRL1 ( *(cc2538_reg_t*)0x400887b0 ) /**< RF observation mux control */
#define RFCORE_XREG_RFC_OBS_CTRL2 ( *(cc2538_reg_t*)0x400887b4 ) /**< RF observation mux control */
#define RFCORE_XREG_TXFILTCFG ( *(cc2538_reg_t*)0x400887e8 ) /**< RF TX filter configuration */
#define RFCORE_SFR_MTCSPCFG ( *(cc2538_reg_t*)0x40088800 ) /**< RF MAC Timer event configuration */
#define RFCORE_SFR_MTCTRL ( *(cc2538_reg_t*)0x40088804 ) /**< RF MAC Timer control register */
#define RFCORE_SFR_MTIRQM ( *(cc2538_reg_t*)0x40088808 ) /**< RF MAC Timer interrupt mask */
#define RFCORE_SFR_MTIRQF ( *(cc2538_reg_t*)0x4008880c ) /**< RF MAC Timer interrupt flags */
#define RFCORE_SFR_MTMSEL ( *(cc2538_reg_t*)0x40088810 ) /**< RF MAC Timer multiplex select */
#define RFCORE_SFR_MTM0 ( *(cc2538_reg_t*)0x40088814 ) /**< RF MAC Timer multiplexed register 0 */
#define RFCORE_SFR_MTM1 ( *(cc2538_reg_t*)0x40088818 ) /**< RF MAC Timer multiplexed register 1 */
#define RFCORE_SFR_MTMOVF2 ( *(cc2538_reg_t*)0x4008881c ) /**< RF MAC Timer multiplexed overflow register 2 */
#define RFCORE_SFR_MTMOVF1 ( *(cc2538_reg_t*)0x40088820 ) /**< RF MAC Timer multiplexed overflow register 1 */
#define RFCORE_SFR_MTMOVF0 ( *(cc2538_reg_t*)0x40088824 ) /**< RF MAC Timer multiplexed overflow register 0 */
#define RFCORE_SFR_RFDATA ( *(cc2538_reg_t*)0x40088828 ) /**< RF Tx/Rx FIFO */
#define RFCORE_SFR_RFERRF ( *(cc2538_reg_t*)0x4008882c ) /**< RF error interrupt flags */
#define RFCORE_SFR_RFIRQF1 ( *(cc2538_reg_t*)0x40088830 ) /**< RF interrupt flags */
#define RFCORE_SFR_RFIRQF0 ( *(cc2538_reg_t*)0x40088834 ) /**< RF interrupt flags */
#define RFCORE_SFR_RFST ( *(cc2538_reg_t*)0x40088838 ) /**< RF CSMA-CA/strobe processor */
#define USB_ADDR ( *(cc2538_reg_t*)0x40089000 ) /**< USB Function address */
#define USB_POW ( *(cc2538_reg_t*)0x40089004 ) /**< USB Power management and control register */
#define USB_IIF ( *(cc2538_reg_t*)0x40089008 ) /**< USB Interrupt flags for endpoint 0 and IN endpoints 1-5 */
#define USB_OIF ( *(cc2538_reg_t*)0x40089010 ) /**< USB Interrupt flags for OUT endpoints 1-5 */
#define USB_CIF ( *(cc2538_reg_t*)0x40089018 ) /**< USB Common USB interrupt flags */
#define USB_IIE ( *(cc2538_reg_t*)0x4008901c ) /**< USB Interrupt enable mask for IN endpoints 1-5 and endpoint 0 */
#define USB_OIE ( *(cc2538_reg_t*)0x40089024 ) /**< USB Interrupt enable mask for OUT endpoints 1-5 */
#define USB_CIE ( *(cc2538_reg_t*)0x4008902c ) /**< USB Common USB interrupt enable mask */
#define USB_FRML ( *(cc2538_reg_t*)0x40089030 ) /**< USB Frame number (low byte) */
#define USB_FRMH ( *(cc2538_reg_t*)0x40089034 ) /**< USB Frame number (high byte) */
#define USB_INDEX ( *(cc2538_reg_t*)0x40089038 ) /**< USB Index register for selecting the endpoint status and control registers */
#define USB_CTRL ( *(cc2538_reg_t*)0x4008903c ) /**< USB USB peripheral control register */
#define USB_MAXI ( *(cc2538_reg_t*)0x40089040 ) /**< USB Indexed register: */
#define USB_CS0_CSIL ( *(cc2538_reg_t*)0x40089044 ) /**< USB Indexed register: */
#define USB_CSIH ( *(cc2538_reg_t*)0x40089048 ) /**< USB Indexed register: */
#define USB_MAXO ( *(cc2538_reg_t*)0x4008904c ) /**< USB Indexed register: */
#define USB_CSOL ( *(cc2538_reg_t*)0x40089050 ) /**< USB Indexed register: */
#define USB_CSOH ( *(cc2538_reg_t*)0x40089054 ) /**< USB Indexed register: */
#define USB_CNT0_CNTL ( *(cc2538_reg_t*)0x40089058 ) /**< USB Indexed register: */
#define USB_CNTH ( *(cc2538_reg_t*)0x4008905c ) /**< USB Indexed register: */
#define USB_F0 ( *(cc2538_reg_t*)0x40089080 ) /**< USB Endpoint 0 FIFO */
#define USB_F1 ( *(cc2538_reg_t*)0x40089088 ) /**< USB IN/OUT endpoint 1 FIFO */
#define USB_F2 ( *(cc2538_reg_t*)0x40089090 ) /**< USB IN/OUT endpoint 2 FIFO */
#define USB_F3 ( *(cc2538_reg_t*)0x40089098 ) /**< USB IN/OUT endpoint 3 FIFO */
#define USB_F4 ( *(cc2538_reg_t*)0x400890a0 ) /**< USB IN/OUT endpoint 4 FIFO */
#define USB_F5 ( *(cc2538_reg_t*)0x400890a8 ) /**< USB IN/OUT endpoint 5 FIFO */
#define AES_DMAC_CH0_CTRL ( *(cc2538_reg_t*)0x4008b000 ) /**< AES Channel control */
#define AES_DMAC_CH0_EXTADDR ( *(cc2538_reg_t*)0x4008b004 ) /**< AES Channel external address */
#define AES_DMAC_CH0_DMALENGTH ( *(cc2538_reg_t*)0x4008b00c ) /**< AES Channel DMA length */
#define AES_DMAC_STATUS ( *(cc2538_reg_t*)0x4008b018 ) /**< AES DMAC status */
#define AES_DMAC_SWRES ( *(cc2538_reg_t*)0x4008b01c ) /**< AES DMAC software reset register */
#define AES_DMAC_CH1_CTRL ( *(cc2538_reg_t*)0x4008b020 ) /**< AES Channel control */
#define AES_DMAC_CH1_EXTADDR ( *(cc2538_reg_t*)0x4008b024 ) /**< AES Channel external address */
#define AES_DMAC_CH1_DMALENGTH ( *(cc2538_reg_t*)0x4008b02c ) /**< AES Channel DMA length */
#define AES_DMAC_MST_RUNPARAMS ( *(cc2538_reg_t*)0x4008b078 ) /**< AES DMAC master run-time parameters */
#define AES_DMAC_PERSR ( *(cc2538_reg_t*)0x4008b07c ) /**< AES DMAC port error raw status register */
#define AES_DMAC_OPTIONS ( *(cc2538_reg_t*)0x4008b0f8 ) /**< AES DMAC options register */
#define AES_DMAC_VERSION ( *(cc2538_reg_t*)0x4008b0fc ) /**< AES DMAC version register */
#define AES_KEY_STORE_WRITE_AREA ( *(cc2538_reg_t*)0x4008b400 ) /**< AES Key store write area register */
#define AES_KEY_STORE_WRITTEN_AREA ( *(cc2538_reg_t*)0x4008b404 ) /**< AES Key store written area register */
#define AES_KEY_STORE_SIZE ( *(cc2538_reg_t*)0x4008b408 ) /**< AES Key store size register */
#define AES_KEY_STORE_READ_AREA ( *(cc2538_reg_t*)0x4008b40c ) /**< AES Key store read area register */
#define AES_AES_KEY2_0 ( *(cc2538_reg_t*)0x4008b500 ) /**< AES_KEY2_0 / AES_GHASH_H_IN_0 */
#define AES_AES_KEY2_1 ( *(cc2538_reg_t*)0x4008b504 ) /**< AES_KEY2_1 / AES_GHASH_H_IN_1 */
#define AES_AES_KEY2_2 ( *(cc2538_reg_t*)0x4008b508 ) /**< AES_KEY2_2 / AES_GHASH_H_IN_2 */
#define AES_AES_KEY2_3 ( *(cc2538_reg_t*)0x4008b50c ) /**< AES_KEY2_3 / AES_GHASH_H_IN_3 */
#define AES_AES_KEY3_0 ( *(cc2538_reg_t*)0x4008b510 ) /**< AES_KEY3_0 / AES_KEY2_4 */
#define AES_AES_KEY3_1 ( *(cc2538_reg_t*)0x4008b514 ) /**< AES_KEY3_1 / AES_KEY2_5 */
#define AES_AES_KEY3_2 ( *(cc2538_reg_t*)0x4008b518 ) /**< AES_KEY3_2 / AES_KEY2_6 */
#define AES_AES_KEY3_3 ( *(cc2538_reg_t*)0x4008b51c ) /**< AES_KEY3_3 / AES_KEY2_7 */
#define AES_AES_IV_0 ( *(cc2538_reg_t*)0x4008b540 ) /**< AES initialization vector registers */
#define AES_AES_IV_1 ( *(cc2538_reg_t*)0x4008b544 ) /**< AES initialization vector registers */
#define AES_AES_IV_2 ( *(cc2538_reg_t*)0x4008b548 ) /**< AES initialization vector registers */
#define AES_AES_IV_3 ( *(cc2538_reg_t*)0x4008b54c ) /**< AES initialization vector registers */
#define AES_AES_CTRL ( *(cc2538_reg_t*)0x4008b550 ) /**< AES input/output buffer control and mode register */
#define AES_AES_C_LENGTH_0 ( *(cc2538_reg_t*)0x4008b554 ) /**< AES crypto length registers (LSW) */
#define AES_AES_C_LENGTH_1 ( *(cc2538_reg_t*)0x4008b558 ) /**< AES crypto length registers (MSW) */
#define AES_AES_AUTH_LENGTH ( *(cc2538_reg_t*)0x4008b55c ) /**< AES Authentication length register */
#define AES_AES_DATA_IN_OUT_0 ( *(cc2538_reg_t*)0x4008b560 ) /**< AES Data input/output registers */
#define AES_AES_DATA_IN_OUT_1 ( *(cc2538_reg_t*)0x4008b564 ) /**< AES Data Input/Output Registers */
#define AES_AES_DATA_IN_OUT_2 ( *(cc2538_reg_t*)0x4008b568 ) /**< AES Data Input/Output Registers */
#define AES_AES_DATA_IN_OUT_3 ( *(cc2538_reg_t*)0x4008b56c ) /**< AES Data Input/Output Registers */
#define AES_AES_TAG_OUT_0 ( *(cc2538_reg_t*)0x4008b570 ) /**< AES TAG register 0 */
#define AES_AES_TAG_OUT_1 ( *(cc2538_reg_t*)0x4008b574 ) /**< AES TAG register 1 */
#define AES_AES_TAG_OUT_2 ( *(cc2538_reg_t*)0x4008b578 ) /**< AES TAG register 2 */
#define AES_AES_TAG_OUT_3 ( *(cc2538_reg_t*)0x4008b57c ) /**< AES TAG register 3 */
#define AES_HASH_DATA_IN_0 ( *(cc2538_reg_t*)0x4008b600 ) /**< AES HASH data input register 0 */
#define AES_HASH_DATA_IN_1 ( *(cc2538_reg_t*)0x4008b604 ) /**< AES HASH data input register 1 */
#define AES_HASH_DATA_IN_2 ( *(cc2538_reg_t*)0x4008b608 ) /**< AES HASH data input register 2 */
#define AES_HASH_DATA_IN_3 ( *(cc2538_reg_t*)0x4008b60c ) /**< AES HASH data input register 3 */
#define AES_HASH_DATA_IN_4 ( *(cc2538_reg_t*)0x4008b610 ) /**< AES HASH data input register 4 */
#define AES_HASH_DATA_IN_5 ( *(cc2538_reg_t*)0x4008b614 ) /**< AES HASH data input register 5 */
#define AES_HASH_DATA_IN_6 ( *(cc2538_reg_t*)0x4008b618 ) /**< AES HASH data input register 6 */
#define AES_HASH_DATA_IN_7 ( *(cc2538_reg_t*)0x4008b61c ) /**< AES HASH data input register 7 */
#define AES_HASH_DATA_IN_8 ( *(cc2538_reg_t*)0x4008b620 ) /**< AES HASH data input register 8 */
#define AES_HASH_DATA_IN_9 ( *(cc2538_reg_t*)0x4008b624 ) /**< AES HASH data input register 9 */
#define AES_HASH_DATA_IN_10 ( *(cc2538_reg_t*)0x4008b628 ) /**< AES HASH data input register 10 */
#define AES_HASH_DATA_IN_11 ( *(cc2538_reg_t*)0x4008b62c ) /**< AES HASH data input register 11 */
#define AES_HASH_DATA_IN_12 ( *(cc2538_reg_t*)0x4008b630 ) /**< AES HASH data input register 12 */
#define AES_HASH_DATA_IN_13 ( *(cc2538_reg_t*)0x4008b634 ) /**< AES HASH data input register 13 */
#define AES_HASH_DATA_IN_14 ( *(cc2538_reg_t*)0x4008b638 ) /**< AES HASH data input register 14 */
#define AES_HASH_DATA_IN_15 ( *(cc2538_reg_t*)0x4008b63c ) /**< AES HASH data input register 15 */
#define AES_HASH_IO_BUF_CTRL ( *(cc2538_reg_t*)0x4008b640 ) /**< AES Input/output buffer control and status register */
#define AES_HASH_MODE_IN ( *(cc2538_reg_t*)0x4008b644 ) /**< AES Hash mode register */
#define AES_HASH_LENGTH_IN_L ( *(cc2538_reg_t*)0x4008b648 ) /**< AES Hash length register */
#define AES_HASH_LENGTH_IN_H ( *(cc2538_reg_t*)0x4008b64c ) /**< AES Hash length register */
#define AES_HASH_DIGEST_A ( *(cc2538_reg_t*)0x4008b650 ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_B ( *(cc2538_reg_t*)0x4008b654 ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_C ( *(cc2538_reg_t*)0x4008b658 ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_D ( *(cc2538_reg_t*)0x4008b65c ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_E ( *(cc2538_reg_t*)0x4008b660 ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_F ( *(cc2538_reg_t*)0x4008b664 ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_G ( *(cc2538_reg_t*)0x4008b668 ) /**< AES Hash digest registers */
#define AES_HASH_DIGEST_H ( *(cc2538_reg_t*)0x4008b66c ) /**< AES Hash digest registers */
#define AES_CTRL_ALG_SEL ( *(cc2538_reg_t*)0x4008b700 ) /**< AES Algorithm select */
#define AES_CTRL_PROT_EN ( *(cc2538_reg_t*)0x4008b704 ) /**< AES Master PROT privileged access enable */
#define AES_CTRL_SW_RESET ( *(cc2538_reg_t*)0x4008b740 ) /**< AES Software reset */
#define AES_CTRL_INT_CFG ( *(cc2538_reg_t*)0x4008b780 ) /**< AES Interrupt configuration */
#define AES_CTRL_INT_EN ( *(cc2538_reg_t*)0x4008b784 ) /**< AES Interrupt enable */
#define AES_CTRL_INT_CLR ( *(cc2538_reg_t*)0x4008b788 ) /**< AES Interrupt clear */
#define AES_CTRL_INT_SET ( *(cc2538_reg_t*)0x4008b78c ) /**< AES Interrupt set */
#define AES_CTRL_INT_STAT ( *(cc2538_reg_t*)0x4008b790 ) /**< AES Interrupt status */
#define AES_CTRL_OPTIONS ( *(cc2538_reg_t*)0x4008b7f8 ) /**< AES Options register */
#define AES_CTRL_VERSION ( *(cc2538_reg_t*)0x4008b7fc ) /**< AES Version register */
#define SYS_CTRL_CLOCK_CTRL ( *(cc2538_reg_t*)0x400d2000 ) /**< Clock control register */
#define SYS_CTRL_CLOCK_STA ( *(cc2538_reg_t*)0x400d2004 ) /**< Clock status register */
#define SYS_CTRL_RCGCGPT ( *(cc2538_reg_t*)0x400d2008 ) /**< Module clocks for GPT[3:0] when the CPU is in active (run) mode */
#define SYS_CTRL_SCGCGPT ( *(cc2538_reg_t*)0x400d200c ) /**< Module clocks for GPT[3:0] when the CPU is in sleep mode */
#define SYS_CTRL_DCGCGPT ( *(cc2538_reg_t*)0x400d2010 ) /**< Module clocks for GPT[3:0] when the CPU is in PM0 */
#define SYS_CTRL_SRGPT ( *(cc2538_reg_t*)0x400d2014 ) /**< Reset for GPT[3:0]. */
#define SYS_CTRL_RCGCSSI ( *(cc2538_reg_t*)0x400d2018 ) /**< Module clocks for SSI[1:0] when the CPU is in active (run) mode */
#define SYS_CTRL_SCGCSSI ( *(cc2538_reg_t*)0x400d201c ) /**< Module clocks for SSI[1:0] when the CPU is insSleep mode */
#define SYS_CTRL_DCGCSSI ( *(cc2538_reg_t*)0x400d2020 ) /**< Module clocks for SSI[1:0] when the CPU is in PM0 */
#define SYS_CTRL_SRSSI ( *(cc2538_reg_t*)0x400d2024 ) /**< Reset for SSI[1:0]. */
#define SYS_CTRL_RCGCUART ( *(cc2538_reg_t*)0x400d2028 ) /**< Module clocks for UART[1:0] when the CPU is in active (run) mode */
#define SYS_CTRL_SCGCUART ( *(cc2538_reg_t*)0x400d202c ) /**< Module clocks for UART[1:0] when the CPU is in sleep mode */
#define SYS_CTRL_DCGCUART ( *(cc2538_reg_t*)0x400d2030 ) /**< Module clocks for UART[1:0] when the CPU is in PM0 */
#define SYS_CTRL_SRUART ( *(cc2538_reg_t*)0x400d2034 ) /**< Reset for UART[1:0]. */
#define SYS_CTRL_RCGCI2C ( *(cc2538_reg_t*)0x400d2038 ) /**< Module clocks for I2C when the CPU is in active (run) mode */
#define SYS_CTRL_SCGCI2C ( *(cc2538_reg_t*)0x400d203c ) /**< Module clocks for I2C when the CPU is in sleep mode */
#define SYS_CTRL_DCGCI2C ( *(cc2538_reg_t*)0x400d2040 ) /**< Module clocks for I2C when the CPU is in PM0 */
#define SYS_CTRL_SRI2C ( *(cc2538_reg_t*)0x400d2044 ) /**< Reset for I2C. */
#define SYS_CTRL_RCGCSEC ( *(cc2538_reg_t*)0x400d2048 ) /**< Module clocks for the security module when the CPU is in active (run) mode */
#define SYS_CTRL_SCGCSEC ( *(cc2538_reg_t*)0x400d204c ) /**< Module clocks for the security module when the CPU is in sleep mode */
#define SYS_CTRL_DCGCSEC ( *(cc2538_reg_t*)0x400d2050 ) /**< Module clocks for the security module when the CPU is in PM0 */
#define SYS_CTRL_SRSEC ( *(cc2538_reg_t*)0x400d2054 ) /**< Reset for the security module. */
#define SYS_CTRL_PMCTL ( *(cc2538_reg_t*)0x400d2058 ) /**< Power mode. */
#define SYS_CTRL_SRCRC ( *(cc2538_reg_t*)0x400d205c ) /**< CRC on state retention. */
#define SYS_CTRL_PWRDBG ( *(cc2538_reg_t*)0x400d2074 ) /**< Power debug register */
#define SYS_CTRL_CLD ( *(cc2538_reg_t*)0x400d2080 ) /**< This register controls the clock loss detection feature. */
#define SYS_CTRL_IWE ( *(cc2538_reg_t*)0x400d2094 ) /**< This register controls interrupt wake-up. */
#define SYS_CTRL_I_MAP ( *(cc2538_reg_t*)0x400d2098 ) /**< This register selects which interrupt map to be used. */
#define SYS_CTRL_RCGCRFC ( *(cc2538_reg_t*)0x400d20a8 ) /**< This register defines the module clocks for RF CORE when the CPU is in active (run) mode */
#define SYS_CTRL_SCGCRFC ( *(cc2538_reg_t*)0x400d20ac ) /**< This register defines the module clocks for RF CORE when the CPU is in sleep mode */
#define SYS_CTRL_DCGCRFC ( *(cc2538_reg_t*)0x400d20b0 ) /**< This register defines the module clocks for RF CORE when the CPU is in PM0 */
#define SYS_CTRL_EMUOVR ( *(cc2538_reg_t*)0x400d20b4 ) /**< This register defines the emulator override controls for power mode and peripheral clock gate. */
#define FLASH_CTRL_FCTL ( *(cc2538_reg_t*)0x400d3008 ) /**< Flash control */
#define FLASH_CTRL_FADDR ( *(cc2538_reg_t*)0x400d300c ) /**< Flash address */
#define FLASH_CTRL_FWDATA ( *(cc2538_reg_t*)0x400d3010 ) /**< Flash data */
#define FLASH_CTRL_DIECFG0 ( *(cc2538_reg_t*)0x400d3014 ) /**< Flash Die Configuration 0 */
#define FLASH_CTRL_DIECFG1 ( *(cc2538_reg_t*)0x400d3018 ) /**< Flash Die Configuration 1 */
#define FLASH_CTRL_DIECFG2 ( *(cc2538_reg_t*)0x400d301c ) /**< Flash Die Configuration 2 */
#define IOC_PA0_SEL ( *(cc2538_reg_t*)0x400d4000 ) /**< Peripheral select control for PA0 */
#define IOC_PA1_SEL ( *(cc2538_reg_t*)0x400d4004 ) /**< Peripheral select control for PA1 */
#define IOC_PA2_SEL ( *(cc2538_reg_t*)0x400d4008 ) /**< Peripheral select control for PA2 */
#define IOC_PA3_SEL ( *(cc2538_reg_t*)0x400d400c ) /**< Peripheral select control for PA3 */
#define IOC_PA4_SEL ( *(cc2538_reg_t*)0x400d4010 ) /**< Peripheral select control for PA4 */
#define IOC_PA5_SEL ( *(cc2538_reg_t*)0x400d4014 ) /**< Peripheral select control for PA5 */
#define IOC_PA6_SEL ( *(cc2538_reg_t*)0x400d4018 ) /**< Peripheral select control for PA6 */
#define IOC_PA7_SEL ( *(cc2538_reg_t*)0x400d401c ) /**< Peripheral select control for PA7 */
#define IOC_PB0_SEL ( *(cc2538_reg_t*)0x400d4020 ) /**< Peripheral select control for PB0 */
#define IOC_PB1_SEL ( *(cc2538_reg_t*)0x400d4024 ) /**< Peripheral select control for PB1 */
#define IOC_PB2_SEL ( *(cc2538_reg_t*)0x400d4028 ) /**< Peripheral select control for PB2 */
#define IOC_PB3_SEL ( *(cc2538_reg_t*)0x400d402c ) /**< Peripheral select control for PB3 */
#define IOC_PB4_SEL ( *(cc2538_reg_t*)0x400d4030 ) /**< Peripheral select control for PB4 */
#define IOC_PB5_SEL ( *(cc2538_reg_t*)0x400d4034 ) /**< Peripheral select control for PB5 */
#define IOC_PB6_SEL ( *(cc2538_reg_t*)0x400d4038 ) /**< Peripheral select control for PB6 */
#define IOC_PB7_SEL ( *(cc2538_reg_t*)0x400d403c ) /**< Peripheral select control for PB7 */
#define IOC_PC0_SEL ( *(cc2538_reg_t*)0x400d4040 ) /**< Peripheral select control for PC0 */
#define IOC_PC1_SEL ( *(cc2538_reg_t*)0x400d4044 ) /**< Peripheral select control for PC1 */
#define IOC_PC2_SEL ( *(cc2538_reg_t*)0x400d4048 ) /**< Peripheral select control for PC2 */
#define IOC_PC3_SEL ( *(cc2538_reg_t*)0x400d404c ) /**< Peripheral select control for PC3 */
#define IOC_PC4_SEL ( *(cc2538_reg_t*)0x400d4050 ) /**< Peripheral select control for PC4 */
#define IOC_PC5_SEL ( *(cc2538_reg_t*)0x400d4054 ) /**< Peripheral select control for PC5 */
#define IOC_PC6_SEL ( *(cc2538_reg_t*)0x400d4058 ) /**< Peripheral select control for PC6 */
#define IOC_PC7_SEL ( *(cc2538_reg_t*)0x400d405c ) /**< Peripheral select control for PC7 */
#define IOC_PD0_SEL ( *(cc2538_reg_t*)0x400d4060 ) /**< Peripheral select control for PD0 */
#define IOC_PD1_SEL ( *(cc2538_reg_t*)0x400d4064 ) /**< Peripheral select control for PD1 */
#define IOC_PD2_SEL ( *(cc2538_reg_t*)0x400d4068 ) /**< Peripheral select control for PD2 */
#define IOC_PD3_SEL ( *(cc2538_reg_t*)0x400d406c ) /**< Peripheral select control for PD3 */
#define IOC_PD4_SEL ( *(cc2538_reg_t*)0x400d4070 ) /**< Peripheral select control for PD4 */
#define IOC_PD5_SEL ( *(cc2538_reg_t*)0x400d4074 ) /**< Peripheral select control for PD5 */
#define IOC_PD6_SEL ( *(cc2538_reg_t*)0x400d4078 ) /**< Peripheral select control for PD6 */
#define IOC_PD7_SEL ( *(cc2538_reg_t*)0x400d407c ) /**< Peripheral select control for PD7 */
#define IOC_PA0_OVER ( *(cc2538_reg_t*)0x400d4080 ) /**< Overide configuration register for PA0. */
#define IOC_PA1_OVER ( *(cc2538_reg_t*)0x400d4084 ) /**< Overide configuration register for PA1. */
#define IOC_PA2_OVER ( *(cc2538_reg_t*)0x400d4088 ) /**< Overide configuration register for PA2. */
#define IOC_PA3_OVER ( *(cc2538_reg_t*)0x400d408c ) /**< Overide configuration register for PA3. */
#define IOC_PA4_OVER ( *(cc2538_reg_t*)0x400d4090 ) /**< Overide configuration register for PA4. */
#define IOC_PA5_OVER ( *(cc2538_reg_t*)0x400d4094 ) /**< Overide configuration register for PA5. */
#define IOC_PA6_OVER ( *(cc2538_reg_t*)0x400d4098 ) /**< Overide configuration register for PA6. */
#define IOC_PA7_OVER ( *(cc2538_reg_t*)0x400d409c ) /**< Overide configuration register for PA7. */
#define IOC_PB0_OVER ( *(cc2538_reg_t*)0x400d40a0 ) /**< Overide configuration register for PB0. */
#define IOC_PB1_OVER ( *(cc2538_reg_t*)0x400d40a4 ) /**< Overide configuration register for PB1. */
#define IOC_PB2_OVER ( *(cc2538_reg_t*)0x400d40a8 ) /**< Overide configuration register for PB2. */
#define IOC_PB3_OVER ( *(cc2538_reg_t*)0x400d40ac ) /**< Overide configuration register for PB3. */
#define IOC_PB4_OVER ( *(cc2538_reg_t*)0x400d40b0 ) /**< Overide configuration register for PB4. */
#define IOC_PB5_OVER ( *(cc2538_reg_t*)0x400d40b4 ) /**< Overide configuration register for PB5. */
#define IOC_PB6_OVER ( *(cc2538_reg_t*)0x400d40b8 ) /**< Overide configuration register for PB6. */
#define IOC_PB7_OVER ( *(cc2538_reg_t*)0x400d40bc ) /**< Overide configuration register for PB7. */
#define IOC_PC0_OVER ( *(cc2538_reg_t*)0x400d40c0 ) /**< Overide configuration register for PC0. PC0 has high drive capability. */
#define IOC_PC1_OVER ( *(cc2538_reg_t*)0x400d40c4 ) /**< Overide configuration register for PC1. PC1 has high drive capability. */
#define IOC_PC2_OVER ( *(cc2538_reg_t*)0x400d40c8 ) /**< Overide configuration register for PC2. PC2 has high drive capability. */
#define IOC_PC3_OVER ( *(cc2538_reg_t*)0x400d40cc ) /**< Overide configuration register for PC3. PC3 has high drive capability. */
#define IOC_PC4_OVER ( *(cc2538_reg_t*)0x400d40d0 ) /**< Overide configuration register for PC4. */
#define IOC_PC5_OVER ( *(cc2538_reg_t*)0x400d40d4 ) /**< Overide configuration register for PC5. */
#define IOC_PC6_OVER ( *(cc2538_reg_t*)0x400d40d8 ) /**< Overide configuration register for PC6. */
#define IOC_PC7_OVER ( *(cc2538_reg_t*)0x400d40dc ) /**< Overide configuration register for PC7. */
#define IOC_PD0_OVER ( *(cc2538_reg_t*)0x400d40e0 ) /**< Overide configuration register for PD0. */
#define IOC_PD1_OVER ( *(cc2538_reg_t*)0x400d40e4 ) /**< Overide configuration register for PD1. */
#define IOC_PD2_OVER ( *(cc2538_reg_t*)0x400d40e8 ) /**< Overide configuration register for PD2. */
#define IOC_PD3_OVER ( *(cc2538_reg_t*)0x400d40ec ) /**< Overide configuration register for PD3. */
#define IOC_PD4_OVER ( *(cc2538_reg_t*)0x400d40f0 ) /**< Overide configuration register for PD4. */
#define IOC_PD5_OVER ( *(cc2538_reg_t*)0x400d40f4 ) /**< Overide configuration register for PD5. */
#define IOC_PD6_OVER ( *(cc2538_reg_t*)0x400d40f8 ) /**< Overide configuration register for PD6. */
#define IOC_PD7_OVER ( *(cc2538_reg_t*)0x400d40fc ) /**< Overide configuration register for PD7. */
#define IOC_UARTRXD_UART0 ( *(cc2538_reg_t*)0x400d4100 ) /**< Pin selection for UART0 RX. */
#define IOC_UARTCTS_UART1 ( *(cc2538_reg_t*)0x400d4104 ) /**< Pin selection for UART1 CTS. */
#define IOC_UARTRXD_UART1 ( *(cc2538_reg_t*)0x400d4108 ) /**< Pin selection for UART1 RX. */
#define IOC_CLK_SSI_SSI0 ( *(cc2538_reg_t*)0x400d410c ) /**< Pin selection for SSI0 CLK. */
#define IOC_SSIRXD_SSI0 ( *(cc2538_reg_t*)0x400d4110 ) /**< Pin selection for SSI0 RX. */
#define IOC_SSIFSSIN_SSI0 ( *(cc2538_reg_t*)0x400d4114 ) /**< Pin selection for SSI0 FSSIN. */
#define IOC_CLK_SSIIN_SSI0 ( *(cc2538_reg_t*)0x400d4118 ) /**< Pin selection for SSI0 CLK_SSIN. */
#define IOC_CLK_SSI_SSI1 ( *(cc2538_reg_t*)0x400d411c ) /**< Pin selection for SSI1 CLK. */
#define IOC_SSIRXD_SSI1 ( *(cc2538_reg_t*)0x400d4120 ) /**< Pin selection for SSI1 RX. */
#define IOC_SSIFSSIN_SSI1 ( *(cc2538_reg_t*)0x400d4124 ) /**< Pin selection for SSI1 FSSIN. */
#define IOC_CLK_SSIIN_SSI1 ( *(cc2538_reg_t*)0x400d4128 ) /**< Pin selection for SSI1 CLK_SSIN. */
#define IOC_I2CMSSDA ( *(cc2538_reg_t*)0x400d412c ) /**< Pin selection for I2C SDA. */
#define IOC_I2CMSSCL ( *(cc2538_reg_t*)0x400d4130 ) /**< Pin selection for I2C SCL. */
#define IOC_GPT0OCP1 ( *(cc2538_reg_t*)0x400d4134 ) /**< Pin selection for GPT0OCP1. */
#define IOC_GPT0OCP2 ( *(cc2538_reg_t*)0x400d4138 ) /**< Pin selection for GPT0OCP2. */
#define IOC_GPT1OCP1 ( *(cc2538_reg_t*)0x400d413c ) /**< Pin selection for GPT1OCP1. */
#define IOC_GPT1OCP2 ( *(cc2538_reg_t*)0x400d4140 ) /**< Pin selection for GPT1OCP2. */
#define IOC_GPT2OCP1 ( *(cc2538_reg_t*)0x400d4144 ) /**< Pin selection for GPT2OCP1. */
#define IOC_GPT2OCP2 ( *(cc2538_reg_t*)0x400d4148 ) /**< Pin selection for GPT2OCP2. */
#define IOC_GPT3OCP1 ( *(cc2538_reg_t*)0x400d414c ) /**< Pin selection for GPT3OCP1. */
#define IOC_GPT3OCP2 ( *(cc2538_reg_t*)0x400d4150 ) /**< Pin selection for GPT3OCP2. */
#define SMWDTHROSC_WDCTL ( *(cc2538_reg_t*)0x400d5000 ) /**< Watchdog Timer Control */
#define SMWDTHROSC_ST0 ( *(cc2538_reg_t*)0x400d5040 ) /**< Sleep Timer 0 count and compare */
#define SMWDTHROSC_ST1 ( *(cc2538_reg_t*)0x400d5044 ) /**< Sleep Timer 1 count and compare */
#define SMWDTHROSC_ST2 ( *(cc2538_reg_t*)0x400d5048 ) /**< Sleep Timer 2 count and compare */
#define SMWDTHROSC_ST3 ( *(cc2538_reg_t*)0x400d504c ) /**< Sleep Timer 3 count and compare */
#define SMWDTHROSC_STLOAD ( *(cc2538_reg_t*)0x400d5050 ) /**< Sleep Timer load status */
#define SMWDTHROSC_STCC ( *(cc2538_reg_t*)0x400d5054 ) /**< Sleep Timer Capture control */
#define SMWDTHROSC_STCS ( *(cc2538_reg_t*)0x400d5058 ) /**< Sleep Timer Capture status */
#define SMWDTHROSC_STCV0 ( *(cc2538_reg_t*)0x400d505c ) /**< Sleep Timer Capture value byte 0 */
#define SMWDTHROSC_STCV1 ( *(cc2538_reg_t*)0x400d5060 ) /**< Sleep Timer Capture value byte 1 */
#define SMWDTHROSC_STCV2 ( *(cc2538_reg_t*)0x400d5064 ) /**< Sleep Timer Capture value byte 2 */
#define SMWDTHROSC_STCV3 ( *(cc2538_reg_t*)0x400d5068 ) /**< Sleep Timer Capture value byte 3 */
#define ANA_REGS_IVCTRL ( *(cc2538_reg_t*)0x400d6004 ) /**< Analog control register */
#define SOC_ADC_ADCCON1 ( *(cc2538_reg_t*)0x400d7000 ) /**< ADC Control Register 1 */
#define SOC_ADC_ADCCON2 ( *(cc2538_reg_t*)0x400d7004 ) /**< ADC Control Register 2 */
#define SOC_ADC_ADCCON3 ( *(cc2538_reg_t*)0x400d7008 ) /**< ADC Control Register 3 */
#define SOC_ADC_ADCL ( *(cc2538_reg_t*)0x400d700c ) /**< Least-significant part of ADC conversion result. */
#define SOC_ADC_ADCH ( *(cc2538_reg_t*)0x400d7010 ) /**< Most-significant part of ADC conversion result. */
#define SOC_ADC_RNDL ( *(cc2538_reg_t*)0x400d7014 ) /**< Random-number-generator data; low byte. */
#define SOC_ADC_RNDH ( *(cc2538_reg_t*)0x400d7018 ) /**< Random-number-generator data; high byte. */
#define SOC_ADC_CMPCTL ( *(cc2538_reg_t*)0x400d7024 ) /**< Analog comparator control and status register. */
#define GPIO_A_DATA ( *(cc2538_reg_t*)0x400d9000 ) /**< GPIO_A Data Register */
#define GPIO_A_DIR ( *(cc2538_reg_t*)0x400d9400 ) /**< GPIO_A data direction register */
#define GPIO_A_IS ( *(cc2538_reg_t*)0x400d9404 ) /**< GPIO_A Interrupt Sense register */
#define GPIO_A_IBE ( *(cc2538_reg_t*)0x400d9408 ) /**< GPIO_A Interrupt Both-Edges register */
#define GPIO_A_IEV ( *(cc2538_reg_t*)0x400d940c ) /**< GPIO_A Interrupt Event Register */
#define GPIO_A_IE ( *(cc2538_reg_t*)0x400d9410 ) /**< GPIO_A Interrupt mask register */
#define GPIO_A_RIS ( *(cc2538_reg_t*)0x400d9414 ) /**< GPIO_A Raw Interrupt Status register */
#define GPIO_A_MIS ( *(cc2538_reg_t*)0x400d9418 ) /**< GPIO_A Masked Interrupt Status register */
#define GPIO_A_IC ( *(cc2538_reg_t*)0x400d941c ) /**< GPIO_A Interrupt Clear register */
#define GPIO_A_AFSEL ( *(cc2538_reg_t*)0x400d9420 ) /**< GPIO_A Alternate Function / mode control select register */
#define GPIO_A_GPIOLOCK ( *(cc2538_reg_t*)0x400d9520 ) /**< GPIO_A Lock register */
#define GPIO_A_GPIOCR ( *(cc2538_reg_t*)0x400d9524 ) /**< GPIO_A Commit Register */
#define GPIO_A_PMUX ( *(cc2538_reg_t*)0x400d9700 ) /**< GPIO_A The PMUX register */
#define GPIO_A_P_EDGE_CTRL ( *(cc2538_reg_t*)0x400d9704 ) /**< GPIO_A The Port Edge Control register */
#define GPIO_A_PI_IEN ( *(cc2538_reg_t*)0x400d9710 ) /**< GPIO_A The Power-up Interrupt Enable register */
#define GPIO_A_IRQ_DETECT_ACK ( *(cc2538_reg_t*)0x400d9718 ) /**< GPIO_A IRQ Detect ACK register */
#define GPIO_A_USB_IRQ_ACK ( *(cc2538_reg_t*)0x400d971c ) /**< GPIO_A IRQ Detect ACK for USB */
#define GPIO_A_IRQ_DETECT_UNMASK ( *(cc2538_reg_t*)0x400d9720 ) /**< GPIO_A IRQ Detect ACK for masked interrupts */
#define GPIO_B_DATA ( *(cc2538_reg_t*)0x400da000 ) /**< GPIO Data Register */
#define GPIO_B_DIR ( *(cc2538_reg_t*)0x400da400 ) /**< GPIO_B data direction register */
#define GPIO_B_IS ( *(cc2538_reg_t*)0x400da404 ) /**< GPIO_B Interrupt Sense register */
#define GPIO_B_IBE ( *(cc2538_reg_t*)0x400da408 ) /**< GPIO_B Interrupt Both-Edges register */
#define GPIO_B_IEV ( *(cc2538_reg_t*)0x400da40c ) /**< GPIO_B Interrupt Event Register */
#define GPIO_B_IE ( *(cc2538_reg_t*)0x400da410 ) /**< GPIO_B Interrupt mask register */
#define GPIO_B_RIS ( *(cc2538_reg_t*)0x400da414 ) /**< GPIO_B Raw Interrupt Status register */
#define GPIO_B_MIS ( *(cc2538_reg_t*)0x400da418 ) /**< GPIO_B Masked Interrupt Status register */
#define GPIO_B_IC ( *(cc2538_reg_t*)0x400da41c ) /**< GPIO_B Interrupt Clear register */
#define GPIO_B_AFSEL ( *(cc2538_reg_t*)0x400da420 ) /**< GPIO_B Alternate Function / mode control select register */
#define GPIO_B_GPIOLOCK ( *(cc2538_reg_t*)0x400da520 ) /**< GPIO_B Lock register */
#define GPIO_B_GPIOCR ( *(cc2538_reg_t*)0x400da524 ) /**< GPIO_B Commit Register */
#define GPIO_B_PMUX ( *(cc2538_reg_t*)0x400da700 ) /**< GPIO_B The PMUX register */
#define GPIO_B_P_EDGE_CTRL ( *(cc2538_reg_t*)0x400da704 ) /**< GPIO_B The Port Edge Control register */
#define GPIO_B_PI_IEN ( *(cc2538_reg_t*)0x400da710 ) /**< GPIO_B The Power-up Interrupt Enable register */
#define GPIO_B_IRQ_DETECT_ACK ( *(cc2538_reg_t*)0x400da718 ) /**< GPIO_B IRQ Detect ACK register */
#define GPIO_B_USB_IRQ_ACK ( *(cc2538_reg_t*)0x400da71c ) /**< GPIO_B IRQ Detect ACK for USB */
#define GPIO_B_IRQ_DETECT_UNMASK ( *(cc2538_reg_t*)0x400da720 ) /**< GPIO_B IRQ Detect ACK for masked interrupts */
#define GPIO_C_DATA ( *(cc2538_reg_t*)0x400db000 ) /**< GPIO_C Data Register */
#define GPIO_C_DIR ( *(cc2538_reg_t*)0x400db400 ) /**< GPIO_C data direction register */
#define GPIO_C_IS ( *(cc2538_reg_t*)0x400db404 ) /**< GPIO_C Interrupt Sense register */
#define GPIO_C_IBE ( *(cc2538_reg_t*)0x400db408 ) /**< GPIO_C Interrupt Both-Edges register */
#define GPIO_C_IEV ( *(cc2538_reg_t*)0x400db40c ) /**< GPIO_C Interrupt Event Register */
#define GPIO_C_IE ( *(cc2538_reg_t*)0x400db410 ) /**< GPIO_C Interrupt mask register */
#define GPIO_C_RIS ( *(cc2538_reg_t*)0x400db414 ) /**< GPIO_C Raw Interrupt Status register */
#define GPIO_C_MIS ( *(cc2538_reg_t*)0x400db418 ) /**< GPIO_C Masked Interrupt Status register */
#define GPIO_C_IC ( *(cc2538_reg_t*)0x400db41c ) /**< GPIO_C Interrupt Clear register */
#define GPIO_C_AFSEL ( *(cc2538_reg_t*)0x400db420 ) /**< GPIO_C Alternate Function / mode control select register */
#define GPIO_C_GPIOLOCK ( *(cc2538_reg_t*)0x400db520 ) /**< GPIO_C Lock register */
#define GPIO_C_GPIOCR ( *(cc2538_reg_t*)0x400db524 ) /**< GPIO_C Commit Register */
#define GPIO_C_PMUX ( *(cc2538_reg_t*)0x400db700 ) /**< GPIO_C The PMUX register */
#define GPIO_C_P_EDGE_CTRL ( *(cc2538_reg_t*)0x400db704 ) /**< GPIO_C The Port Edge Control register */
#define GPIO_C_PI_IEN ( *(cc2538_reg_t*)0x400db710 ) /**< GPIO_C The Power-up Interrupt Enable register */
#define GPIO_C_IRQ_DETECT_ACK ( *(cc2538_reg_t*)0x400db718 ) /**< GPIO_C IRQ Detect ACK register */
#define GPIO_C_USB_IRQ_ACK ( *(cc2538_reg_t*)0x400db71c ) /**< GPIO_C IRQ Detect ACK for USB */
#define GPIO_C_IRQ_DETECT_UNMASK ( *(cc2538_reg_t*)0x400db720 ) /**< GPIO_C IRQ Detect ACK for masked interrupts */
#define GPIO_D_DATA ( *(cc2538_reg_t*)0x400dc000 ) /**< GPIO_D Data Register */
#define GPIO_D_DIR ( *(cc2538_reg_t*)0x400dc400 ) /**< GPIO_D data direction register */
#define GPIO_D_IS ( *(cc2538_reg_t*)0x400dc404 ) /**< GPIO_D Interrupt Sense register */
#define GPIO_D_IBE ( *(cc2538_reg_t*)0x400dc408 ) /**< GPIO_D Interrupt Both-Edges register */
#define GPIO_D_IEV ( *(cc2538_reg_t*)0x400dc40c ) /**< GPIO_D Interrupt Event Register */
#define GPIO_D_IE ( *(cc2538_reg_t*)0x400dc410 ) /**< GPIO_D Interrupt mask register */
#define GPIO_D_RIS ( *(cc2538_reg_t*)0x400dc414 ) /**< GPIO_D Raw Interrupt Status register */
#define GPIO_D_MIS ( *(cc2538_reg_t*)0x400dc418 ) /**< GPIO_D Masked Interrupt Status register */
#define GPIO_D_IC ( *(cc2538_reg_t*)0x400dc41c ) /**< GPIO_D Interrupt Clear register */
#define GPIO_D_AFSEL ( *(cc2538_reg_t*)0x400dc420 ) /**< GPIO_D Alternate Function / mode control select register */
#define GPIO_D_GPIOLOCK ( *(cc2538_reg_t*)0x400dc520 ) /**< GPIO_D Lock register */
#define GPIO_D_GPIOCR ( *(cc2538_reg_t*)0x400dc524 ) /**< GPIO_D Commit Register */
#define GPIO_D_PMUX ( *(cc2538_reg_t*)0x400dc700 ) /**< GPIO_D The PMUX register */
#define GPIO_D_P_EDGE_CTRL ( *(cc2538_reg_t*)0x400dc704 ) /**< GPIO_D The Port Edge Control register */
#define GPIO_D_PI_IEN ( *(cc2538_reg_t*)0x400dc710 ) /**< GPIO_D The Power-up Interrupt Enable register */
#define GPIO_D_IRQ_DETECT_ACK ( *(cc2538_reg_t*)0x400dc718 ) /**< GPIO_D IRQ Detect ACK register */
#define GPIO_D_USB_IRQ_ACK ( *(cc2538_reg_t*)0x400dc71c ) /**< GPIO_D IRQ Detect ACK for USB */
#define GPIO_D_IRQ_DETECT_UNMASK ( *(cc2538_reg_t*)0x400dc720 ) /**< GPIO_D IRQ Detect ACK for masked interrupts */
#define UDMA_STAT ( *(cc2538_reg_t*)0x400ff000 ) /**< DMA status */
#define UDMA_CFG ( *(cc2538_reg_t*)0x400ff004 ) /**< DMA configuration */
#define UDMA_CTLBASE ( *(cc2538_reg_t*)0x400ff008 ) /**< DMA channel control base pointer */
#define UDMA_ALTBASE ( *(cc2538_reg_t*)0x400ff00c ) /**< DMA alternate channel control base pointer */
#define UDMA_WAITSTAT ( *(cc2538_reg_t*)0x400ff010 ) /**< DMA channel wait-on-request status */
#define UDMA_SWREQ ( *(cc2538_reg_t*)0x400ff014 ) /**< DMA channel software request */
#define UDMA_USEBURSTSET ( *(cc2538_reg_t*)0x400ff018 ) /**< DMA channel useburst set */
#define UDMA_USEBURSTCLR ( *(cc2538_reg_t*)0x400ff01c ) /**< DMA channel useburst clear */
#define UDMA_REQMASKSET ( *(cc2538_reg_t*)0x400ff020 ) /**< DMA channel request mask set */
#define UDMA_REQMASKCLR ( *(cc2538_reg_t*)0x400ff024 ) /**< DMA channel request mask clear */
#define UDMA_ENASET ( *(cc2538_reg_t*)0x400ff028 ) /**< DMA channel enable set */
#define UDMA_ENACLR ( *(cc2538_reg_t*)0x400ff02c ) /**< DMA channel enable clear */
#define UDMA_ALTSET ( *(cc2538_reg_t*)0x400ff030 ) /**< DMA channel primary alternate set */
#define UDMA_ALTCLR ( *(cc2538_reg_t*)0x400ff034 ) /**< DMA channel primary alternate clear */
#define UDMA_PRIOSET ( *(cc2538_reg_t*)0x400ff038 ) /**< DMA channel priority set */
#define UDMA_PRIOCLR ( *(cc2538_reg_t*)0x400ff03c ) /**< DMA channel priority clear */
#define UDMA_ERRCLR ( *(cc2538_reg_t*)0x400ff04c ) /**< DMA bus error clear */
#define UDMA_CHASGN ( *(cc2538_reg_t*)0x400ff500 ) /**< DMA channel assignment */
#define UDMA_CHIS ( *(cc2538_reg_t*)0x400ff504 ) /**< DMA channel interrupt status */
#define UDMA_CHMAP0 ( *(cc2538_reg_t*)0x400ff510 ) /**< DMA channel map select 0 */
#define UDMA_CHMAP1 ( *(cc2538_reg_t*)0x400ff514 ) /**< DMA channel map select 1 */
#define UDMA_CHMAP2 ( *(cc2538_reg_t*)0x400ff518 ) /**< DMA channel map select 2 */
#define UDMA_CHMAP3 ( *(cc2538_reg_t*)0x400ff51c ) /**< DMA channel map select 3 */
#define PKA_APTR ( *(cc2538_reg_t*)0x44004000 ) /**< PKA vector A address */
#define PKA_BPTR ( *(cc2538_reg_t*)0x44004004 ) /**< PKA vector B address */
#define PKA_CPTR ( *(cc2538_reg_t*)0x44004008 ) /**< PKA vector C address */
#define PKA_DPTR ( *(cc2538_reg_t*)0x4400400c ) /**< PKA vector D address */
#define PKA_ALENGTH ( *(cc2538_reg_t*)0x44004010 ) /**< PKA vector A length */
#define PKA_BLENGTH ( *(cc2538_reg_t*)0x44004014 ) /**< PKA vector B length */
#define PKA_SHIFT ( *(cc2538_reg_t*)0x44004018 ) /**< PKA bit shift value */
#define PKA_FUNCTION ( *(cc2538_reg_t*)0x4400401c ) /**< PKA function */
#define PKA_COMPARE ( *(cc2538_reg_t*)0x44004020 ) /**< PKA compare result */
#define PKA_MSW ( *(cc2538_reg_t*)0x44004024 ) /**< PKA most-significant-word of result vector */
#define PKA_DIVMSW ( *(cc2538_reg_t*)0x44004028 ) /**< PKA most-significant-word of divide remainder */
#define PKA_SEQ_CTRL ( *(cc2538_reg_t*)0x440040c8 ) /**< PKA sequencer control and status register */
#define PKA_OPTIONS ( *(cc2538_reg_t*)0x440040f4 ) /**< PKA hardware options register */
#define PKA_SW_REV ( *(cc2538_reg_t*)0x440040f8 ) /**< PKA firmware revision and capabilities register */
#define PKA_REVISION ( *(cc2538_reg_t*)0x440040fc ) /**< PKA hardware revision register */
#define CCTEST_IO ( *(cc2538_reg_t*)0x44010000 ) /**< Output strength control */
#define CCTEST_OBSSEL0 ( *(cc2538_reg_t*)0x44010014 ) /**< CCTEST Select output signal on observation output 0 */
#define CCTEST_OBSSEL1 ( *(cc2538_reg_t*)0x44010018 ) /**< CCTEST Select output signal on observation output 1 */
#define CCTEST_OBSSEL2 ( *(cc2538_reg_t*)0x4401001c ) /**< CCTEST Select output signal on observation output 2 */
#define CCTEST_OBSSEL3 ( *(cc2538_reg_t*)0x44010020 ) /**< CCTEST Select output signal on observation output 3 */
#define CCTEST_OBSSEL4 ( *(cc2538_reg_t*)0x44010024 ) /**< CCTEST Select output signal on observation output 4 */
#define CCTEST_OBSSEL5 ( *(cc2538_reg_t*)0x44010028 ) /**< CCTEST Select output signal on observation output 5 */
#define CCTEST_OBSSEL6 ( *(cc2538_reg_t*)0x4401002c ) /**< CCTEST Select output signal on observation output 6 */
#define CCTEST_OBSSEL7 ( *(cc2538_reg_t*)0x44010030 ) /**< CCTEST Select output signal on observation output 7 */
#define CCTEST_TR0 ( *(cc2538_reg_t*)0x44010034 ) /**< CCTEST Test register 0 */
#define CCTEST_USBCTRL ( *(cc2538_reg_t*)0x44010050 ) /**< CCTEST USB PHY stand-by control */
/** @} */
#define XOSC32M_FREQ 32000000 /**< 32 MHz external oscillator/clock frequency */
#define RCOSC16M_FREQ 16000000 /**< 16 MHz internal RC oscillator frequency */
#ifdef __cplusplus
}
#endif
#endif /* _CC2538_ */
/*@}*/

View File

@ -0,0 +1,62 @@
/*
* 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
* @brief Implementation specific CPU configuration options
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef __CPU_CONF_H
#define __CPU_CONF_H
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Kernel configuration
* @{
*/
#define KERNEL_CONF_STACKSIZE_PRINTF 1024
#ifndef KERNEL_CONF_STACKSIZE_DEFAULT
#define KERNEL_CONF_STACKSIZE_DEFAULT 1024
#endif
#define KERNEL_CONF_STACKSIZE_IDLE 512
/** @} */
/**
* @name UART0 buffer size definition for compatibility reasons
* @{
*/
#ifndef UART0_BUFSIZE
#define UART0_BUFSIZE 128
#endif
/** @} */
/**
* @brief length of CPU ID for @ref cpuid_get() in @ref periph/cpuid.h
*/
#ifndef CPUID_ID_LEN
#define CPUID_ID_LEN 8
#endif
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* __CPU_CONF_H */
/** @} */

View File

@ -0,0 +1,154 @@
/*
* 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 gptimer.h
* @brief CC2538 General Purpose Timer (GPTIMER) driver
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef GPTIMER_H
#define GPTIMER_H
#include <stdint.h>
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
#define GPTIMER_NUMOF 4 /**< The CC2538 has four general-purpose timer units. */
#define NUM_CHANNELS_PER_GPTIMER 2 /**< Each G.P. timer unit has two channels: A and B. */
enum {
GPTIMER_ONE_SHOT_MODE = 1, /**< GPTIMER one-shot mode */
GPTIMER_PERIODIC_MODE = 2, /**< GPTIMER periodic mode */
GPTIMER_CAPTURE_MODE = 3, /**< GPTIMER capture mode */
};
enum {
GPTMCFG_32_BIT_TIMER = 0, /**< 32-bit timer configuration */
GPTMCFG_32_BIT_REAL_TIME_CLOCK = 1, /**< 32-bit real-time clock */
GPTMCFG_16_BIT_TIMER = 4, /**< 16-bit timer configuration */
};
/**
* @brief GPTIMER component registers
*/
typedef struct {
cc2538_reg_t CFG; /**< GPTIMER Configuration */
union {
cc2538_reg_t TAMR; /**< GPTIMER Timer A mode */
struct {
cc2538_reg_t TAMR2 : 2; /**< GPTM Timer A mode */
cc2538_reg_t TACRM : 1; /**< GPTM Timer A capture mode */
cc2538_reg_t TAAMS : 1; /**< GPTM Timer A alternate mode */
cc2538_reg_t TACDIR : 1; /**< GPTM Timer A count direction */
cc2538_reg_t TAMIE : 1; /**< GPTM Timer A match interrupt enable */
cc2538_reg_t TAWOT : 1; /**< GPTM Timer A wait-on-trigger */
cc2538_reg_t TASNAPS : 1; /**< GPTM Timer A snap shot mode */
cc2538_reg_t TAILD : 1; /**< GPTM Timer A interval load write */
cc2538_reg_t TAPWMIE : 1; /**< GPTM Timer A PWM interrupt enable */
cc2538_reg_t TAMRSU : 1; /**< Timer A match register update mode */
cc2538_reg_t TAPLO : 1; /**< Legacy PWM operation */
cc2538_reg_t RESERVED5 : 20; /**< Reserved bits */
} TAMRbits;
};
union {
cc2538_reg_t TBMR; /**< GPTIMER Timer B mode */
struct {
cc2538_reg_t TBMR2 : 2; /**< GPTM Timer B mode */
cc2538_reg_t TBCRM : 1; /**< GPTM Timer B capture mode */
cc2538_reg_t TBAMS : 1; /**< GPTM Timer B alternate mode */
cc2538_reg_t TBCDIR : 1; /**< GPTM Timer B count direction */
cc2538_reg_t TBMIE : 1; /**< GPTM Timer B match interrupt enable */
cc2538_reg_t TBWOT : 1; /**< GPTM Timer B wait-on-trigger */
cc2538_reg_t TBSNAPS : 1; /**< GPTM Timer B snap shot mode */
cc2538_reg_t TBILD : 1; /**< GPTM Timer B interval load write */
cc2538_reg_t TBPWMIE : 1; /**< GPTM Timer B PWM interrupt enable */
cc2538_reg_t TBMRSU : 1; /**< Timer B match register update mode */
cc2538_reg_t TBPLO : 1; /**< Legacy PWM operation */
cc2538_reg_t RESERVED6 : 20; /**< Reserved bits */
} TBMRbits;
};
union {
cc2538_reg_t CTL; /**< GPTIMER Control */
struct {
cc2538_reg_t TAEN : 1; /**< GPTM Timer A enable */
cc2538_reg_t TASTALL : 1; /**< GPTM Timer A stall enable */
cc2538_reg_t TAEVENT : 1; /**< GPTM Timer A event mode */
cc2538_reg_t RESERVED1 : 1; /**< Reserved bits */
cc2538_reg_t TAOTE : 1; /**< GPTM Timer A PWM output trigger enable */
cc2538_reg_t TAPWML : 1; /**< GPTM Timer A PWM output level */
cc2538_reg_t RESERVED2 : 1; /**< Reserved bits */
cc2538_reg_t TBEN : 1; /**< GPTM Timer B enable */
cc2538_reg_t TBSTALL : 1; /**< GPTM Timer B stall enable */
cc2538_reg_t TBEVENT : 1; /**< GPTM Timer B event mode */
cc2538_reg_t RESERVED3 : 1; /**< Reserved bits */
cc2538_reg_t TBOTE : 1; /**< GPTM Timer B PWM output trigger enable */
cc2538_reg_t TBPWML : 1; /**< GPTM Timer B PWM output level */
cc2538_reg_t RESERVED4 : 17; /**< Reserved bits */
} CTLbits;
};
cc2538_reg_t SYNC; /**< GPTIMER Synchronize */
cc2538_reg_t RESERVED2; /**< Reserved word */
cc2538_reg_t IMR; /**< GPTIMER Interrupt Mask */
cc2538_reg_t RIS; /**< GPTIMER Raw Interrupt Status */
cc2538_reg_t MIS; /**< GPTIMER Masked Interrupt Status */
cc2538_reg_t ICR; /**< GPTIMER Interrupt Clear */
cc2538_reg_t TAILR; /**< GPTIMER Timer A Interval Load */
cc2538_reg_t TBILR; /**< GPTIMER Timer B Interval Load */
cc2538_reg_t TAMATCHR; /**< GPTIMER Timer A Match */
cc2538_reg_t TBMATCHR; /**< GPTIMER Timer B Match */
cc2538_reg_t TAPR; /**< GPTIMER Timer A Prescale Register */
cc2538_reg_t TBPR; /**< GPTIMER Timer B Prescale Register */
cc2538_reg_t TAPMR; /**< GPTIMER Timer A Prescale Match Register */
cc2538_reg_t TBPMR; /**< GPTIMER Timer B Prescale Match Register */
cc2538_reg_t TAR; /**< GPTIMER Timer A */
cc2538_reg_t TBR; /**< GPTIMER Timer B */
cc2538_reg_t TAV; /**< GPTIMER Timer A Value */
cc2538_reg_t TBV; /**< GPTIMER Timer B Value */
cc2538_reg_t RESERVED3; /**< Reserved word */
cc2538_reg_t TAPS; /**< GPTIMER Timer A Prescale Snapshot */
cc2538_reg_t TBPS; /**< GPTIMER Timer B Prescale Snapshot */
cc2538_reg_t TAPV; /**< GPTIMER Timer A Prescale Value */
cc2538_reg_t TBPV; /**< GPTIMER Timer B Prescale Value */
cc2538_reg_t RESERVED[981];
cc2538_reg_t PP; /**< GPTIMER Peripheral Properties */
} cc2538_gptimer_t;
#define GPTIMER0 ( (cc2538_gptimer_t*)0x40030000 ) /**< GPTIMER0 Instance */
#define GPTIMER1 ( (cc2538_gptimer_t*)0x40031000 ) /**< GPTIMER1 Instance */
#define GPTIMER2 ( (cc2538_gptimer_t*)0x40032000 ) /**< GPTIMER2 Instance */
#define GPTIMER3 ( (cc2538_gptimer_t*)0x40033000 ) /**< GPTIMER3 Instance */
void isr_timer0_chan0(void); /**< RIOT Timer 0 Channel 0 Interrupt Service Routine */
void isr_timer0_chan1(void); /**< RIOT Timer 0 Channel 1 Interrupt Service Routine */
void isr_timer1_chan0(void); /**< RIOT Timer 1 Channel 0 Interrupt Service Routine */
void isr_timer1_chan1(void); /**< RIOT Timer 1 Channel 1 Interrupt Service Routine */
void isr_timer2_chan0(void); /**< RIOT Timer 2 Channel 0 Interrupt Service Routine */
void isr_timer2_chan1(void); /**< RIOT Timer 2 Channel 1 Interrupt Service Routine */
void isr_timer3_chan0(void); /**< RIOT Timer 3 Channel 0 Interrupt Service Routine */
void isr_timer3_chan1(void); /**< RIOT Timer 3 Channel 1 Interrupt Service Routine */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* GPTIMER_H */
/* @} */

View File

@ -0,0 +1,42 @@
/*
* 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
* @brief CPU specific hwtimer configuration options
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef __HWTIMER_CPU_H
#define __HWTIMER_CPU_H
#include "gptimer.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Hardware timer configuration
* @{
*/
#define HWTIMER_MAXTIMERS NUM_CHANNELS_PER_GPTIMER /**< Number of hwtimers */
#define HWTIMER_SPEED 1000000 /**< The hardware timer runs at 1MHz */
#define HWTIMER_MAXTICKS 0xFFFFFFFF /**< 32-bit timer */
/** @} */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* __HWTIMER_CPU_H */
/** @} */

85
cpu/cc2538/include/ioc.h Normal file
View File

@ -0,0 +1,85 @@
/*
* 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.
*/
/**
* @{
*
* @file ioc.h
* @brief CC2538 I/O Control driver
*
* @author Ian Martin <ian@locicontrols.com>
*
* @addtogroup cpu_cc2538
* @{
*
* @defgroup cc2538-ioc CC2538 I/O Control
*
* Header file with declarations for the I/O Control module
* @{
*/
#ifndef IOC_H_
#define IOC_H_
#include <stdint.h>
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
#define IOC_PXX_SEL ( (cc2538_reg_t*)0x400d4000 )
#define IOC_PXX_OVER ( (cc2538_reg_t*)0x400d4080 )
/** @name Peripheral Signal Select Values (for IOC_Pxx_SEL registers)
* @{
*/
enum {
UART0_TXD = 0, /**< UART0 TXD */
UART1_RTS = 1, /**< UART1 RTS */
UART1_TXD = 2, /**< UART1 TXD */
SSI0_TXD = 3, /**< SSI0 TXD */
SSI0_CLKOUT = 4, /**< SSI0 CLKOUT */
SSI0_FSSOUT = 5, /**< SSI0 FSSOUT */
SSI0_STXSER_EN = 6, /**< SSI0 STXSER EN */
SSI1_TXD = 7, /**< SSI1 TXD */
SSI1_CLKOUT = 8, /**< SSI1 CLKOUT */
SSI1_FSSOUT = 9, /**< SSI1 FSSOUT */
SSI1_STXSER_EN = 10, /**< SSI1 STXSER EN */
I2C_CMSSDA = 11, /**< I2C CMSSDA */
I2C_CMSSCL = 12, /**< I2C CMSSCL */
GPT0_ICP1 = 13, /**< GPT0 ICP1 */
GPT0_ICP2 = 14, /**< GPT0 ICP2 */
GPT1_ICP1 = 15, /**< GPT1 ICP1 */
GPT1_ICP2 = 16, /**< GPT1 ICP2 */
GPT2_ICP1 = 17, /**< GPT2 ICP1 */
GPT2_ICP2 = 18, /**< GPT2 ICP2 */
GPT3_ICP1 = 19, /**< GPT3 ICP1 */
GPT3_ICP2 = 20, /**< GPT3 ICP2 */
};
/** @} */
/** @name Values for IOC_PXX_OVER
* @{
*/
#define IOC_OVERRIDE_OE 0x00000008 /**< Output Enable */
#define IOC_OVERRIDE_PUE 0x00000004 /**< Pull Up Enable */
#define IOC_OVERRIDE_PDE 0x00000002 /**< Pull Down Enable */
#define IOC_OVERRIDE_ANA 0x00000001 /**< Analog Enable */
#define IOC_OVERRIDE_DIS 0x00000000 /**< Override Disabled */
/** @} */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* IOC_H_ */
/** @} */
/** @} */
/** @} */

224
cpu/cc2538/include/rfcore.h Normal file
View File

@ -0,0 +1,224 @@
/*
* 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.
*/
/**
* @{
*
* @file rfcore.h
* @brief CC2538 RF core interface
*
* @author Ian Martin <ian@locicontrols.com>
*
* @addtogroup cpu_cc2538
* @{
*
* @defgroup cc2538-rfcore CC2538 RF core interface
* @{
*/
#ifndef CC2538_RFCORE_H
#define CC2538_RFCORE_H
#include "cc2538.h"
/**
* @brief RF Core component registers
*/
typedef struct {
cc2538_reg_t FFSM_SRCRESMASK0; /**< RF Source address matching result */
cc2538_reg_t FFSM_SRCRESMASK1; /**< RF Source address matching result */
cc2538_reg_t FFSM_SRCRESMASK2; /**< RF Source address matching result */
cc2538_reg_t FFSM_SRCRESINDEX; /**< RF Source address matching result */
cc2538_reg_t FFSM_SRCEXTPENDEN0; /**< RF Source address matching control */
cc2538_reg_t FFSM_SRCEXTPENDEN1; /**< RF Source address matching control */
cc2538_reg_t FFSM_SRCEXTPENDEN2; /**< RF Source address matching control */
cc2538_reg_t FFSM_SRCSHORTPENDEN0; /**< RF Source address matching control */
cc2538_reg_t FFSM_SRCSHORTPENDEN1; /**< RF Source address matching control */
cc2538_reg_t FFSM_SRCSHORTPENDEN2; /**< RF Source address matching control */
cc2538_reg_t FFSM_EXT_ADDR0; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR1; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR2; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR3; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR4; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR5; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR6; /**< RF Local address information */
cc2538_reg_t FFSM_EXT_ADDR7; /**< RF Local address information */
cc2538_reg_t FFSM_PAN_ID0; /**< RF Local address information */
cc2538_reg_t FFSM_PAN_ID1; /**< RF Local address information */
cc2538_reg_t FFSM_SHORT_ADDR0; /**< RF Local address information */
cc2538_reg_t FFSM_SHORT_ADDR1; /**< RF Local address information */
cc2538_reg_t RESERVED1[10]; /**< Reserved bytes */
cc2538_reg_t XREG_FRMFILT0; /**< RF Frame Filter 0 */
cc2538_reg_t XREG_FRMFILT1; /**< RF Frame Filter 1 */
cc2538_reg_t XREG_SRCMATCH; /**< RF Source address matching and pending bits */
cc2538_reg_t XREG_SRCSHORTEN0; /**< RF Short address matching */
cc2538_reg_t XREG_SRCSHORTEN1; /**< RF Short address matching */
cc2538_reg_t XREG_SRCSHORTEN2; /**< RF Short address matching */
cc2538_reg_t XREG_SRCEXTEN0; /**< RF Extended address matching */
cc2538_reg_t XREG_SRCEXTEN1; /**< RF Extended address matching */
cc2538_reg_t XREG_SRCEXTEN2; /**< RF Extended address matching */
cc2538_reg_t XREG_FRMCTRL0; /**< RF Frame handling */
cc2538_reg_t XREG_FRMCTRL1; /**< RF Frame handling */
cc2538_reg_t XREG_RXENABLE; /**< RF RX enabling */
cc2538_reg_t XREG_RXMASKSET; /**< RF RX enabling */
cc2538_reg_t XREG_RXMASKCLR; /**< RF RX disabling */
cc2538_reg_t XREG_FREQTUNE; /**< RF Crystal oscillator frequency tuning */
cc2538_reg_t XREG_FREQCTRL; /**< RF Controls the RF frequency */
cc2538_reg_t XREG_TXPOWER; /**< RF Controls the output power */
cc2538_reg_t XREG_TXCTRL; /**< RF Controls the TX settings */
cc2538_reg_t XREG_FSMSTAT0; /**< RF Radio status register */
cc2538_reg_t XREG_FSMSTAT1; /**< RF Radio status register */
cc2538_reg_t XREG_FIFOPCTRL; /**< RF FIFOP threshold */
cc2538_reg_t XREG_FSMCTRL; /**< RF FSM options */
cc2538_reg_t XREG_CCACTRL0; /**< RF CCA threshold */
cc2538_reg_t XREG_CCACTRL1; /**< RF Other CCA Options */
cc2538_reg_t XREG_RSSI; /**< RF RSSI status register */
union {
cc2538_reg_t XREG_RSSISTAT; /**< RF RSSI valid status register */
struct {
cc2538_reg_t RSSI_VALID : 1; /**< RSSI value is valid */
cc2538_reg_t RESERVED : 31; /**< Reserved bits */
} XREG_RSSISTATbits;
};
cc2538_reg_t XREG_RXFIRST; /**< RF First byte in RX FIFO */
cc2538_reg_t XREG_RXFIFOCNT; /**< RF Number of bytes in RX FIFO */
cc2538_reg_t XREG_TXFIFOCNT; /**< RF Number of bytes in TX FIFO */
cc2538_reg_t XREG_RXFIRST_PTR; /**< RF RX FIFO pointer */
cc2538_reg_t XREG_RXLAST_PTR; /**< RF RX FIFO pointer */
cc2538_reg_t XREG_RXP1_PTR; /**< RF RX FIFO pointer */
cc2538_reg_t RESERVED2; /**< Reserved bytes */
cc2538_reg_t XREG_TXFIRST_PTR; /**< RF TX FIFO pointer */
cc2538_reg_t XREG_TXLAST_PTR; /**< RF TX FIFO pointer */
cc2538_reg_t XREG_RFIRQM0; /**< RF interrupt masks */
cc2538_reg_t XREG_RFIRQM1; /**< RF interrupt masks */
cc2538_reg_t XREG_RFERRM; /**< RF error interrupt mask */
cc2538_reg_t RESERVED3; /**< Reserved bytes */
union {
cc2538_reg_t XREG_RFRND; /**< RF Random data */
struct {
cc2538_reg_t IRND : 1; /**< Random bit from the I channel of the receiver */
cc2538_reg_t QRND : 1; /**< Random bit from the Q channel of the receiver */
cc2538_reg_t RESERVED : 30; /**< Reserved bits */
} XREG_RFRNDbits;
};
cc2538_reg_t XREG_MDMCTRL0; /**< RF Controls modem */
cc2538_reg_t XREG_MDMCTRL1; /**< RF Controls modem */
cc2538_reg_t XREG_FREQEST; /**< RF Estimated RF frequency offset */
cc2538_reg_t XREG_RXCTRL; /**< RF Tune receive section */
cc2538_reg_t XREG_FSCTRL; /**< RF Tune frequency synthesizer */
cc2538_reg_t XREG_FSCAL0; /**< RF Tune frequency calibration */
cc2538_reg_t XREG_FSCAL1; /**< RF Tune frequency calibration */
cc2538_reg_t XREG_FSCAL2; /**< RF Tune frequency calibration */
cc2538_reg_t XREG_FSCAL3; /**< RF Tune frequency calibration */
cc2538_reg_t XREG_AGCCTRL0; /**< RF AGC dynamic range control */
cc2538_reg_t XREG_AGCCTRL1; /**< RF AGC reference level */
cc2538_reg_t XREG_AGCCTRL2; /**< RF AGC gain override */
cc2538_reg_t XREG_AGCCTRL3; /**< RF AGC control */
cc2538_reg_t XREG_ADCTEST0; /**< RF ADC tuning */
cc2538_reg_t XREG_ADCTEST1; /**< RF ADC tuning */
cc2538_reg_t XREG_ADCTEST2; /**< RF ADC tuning */
cc2538_reg_t XREG_MDMTEST0; /**< RF Test register for modem */
cc2538_reg_t XREG_MDMTEST1; /**< RF Test Register for Modem */
cc2538_reg_t XREG_DACTEST0; /**< RF DAC override value */
cc2538_reg_t XREG_DACTEST1; /**< RF DAC override value */
cc2538_reg_t XREG_DACTEST2; /**< RF DAC test setting */
cc2538_reg_t XREG_ATEST; /**< RF Analog test control */
cc2538_reg_t XREG_PTEST0; /**< RF Override power-down register */
cc2538_reg_t XREG_PTEST1; /**< RF Override power-down register */
cc2538_reg_t RESERVED4[32]; /**< Reserved bytes */
cc2538_reg_t XREG_CSPCTRL; /**< RF CSP control bit */
cc2538_reg_t XREG_CSPSTAT; /**< RF CSP status register */
cc2538_reg_t XREG_CSPX; /**< RF CSP X data register */
cc2538_reg_t XREG_CSPY; /**< RF CSP Y data register */
cc2538_reg_t XREG_CSPZ; /**< RF CSP Z data register */
cc2538_reg_t XREG_CSPT; /**< RF CSP T data register */
cc2538_reg_t RESERVED5[5]; /**< Reserved bytes */
cc2538_reg_t XREG_RFC_OBS_CTRL0; /**< RF observation mux control */
cc2538_reg_t XREG_RFC_OBS_CTRL1; /**< RF observation mux control */
cc2538_reg_t XREG_RFC_OBS_CTRL2; /**< RF observation mux control */
cc2538_reg_t RESERVED6[12]; /**< Reserved bytes */
cc2538_reg_t XREG_TXFILTCFG; /**< RF TX filter configuration */
cc2538_reg_t RESERVED7[5]; /**< Reserved bytes */
cc2538_reg_t SFR_MTCSPCFG; /**< RF MAC Timer event configuration */
cc2538_reg_t SFR_MTCTRL; /**< RF MAC Timer control register */
cc2538_reg_t SFR_MTIRQM; /**< RF MAC Timer interrupt mask */
cc2538_reg_t SFR_MTIRQF; /**< RF MAC Timer interrupt flags */
cc2538_reg_t SFR_MTMSEL; /**< RF MAC Timer multiplex select */
cc2538_reg_t SFR_MTM0; /**< RF MAC Timer multiplexed register 0 */
cc2538_reg_t SFR_MTM1; /**< RF MAC Timer multiplexed register 1 */
cc2538_reg_t SFR_MTMOVF2; /**< RF MAC Timer multiplexed overflow register 2 */
cc2538_reg_t SFR_MTMOVF1; /**< RF MAC Timer multiplexed overflow register 1 */
cc2538_reg_t SFR_MTMOVF0; /**< RF MAC Timer multiplexed overflow register 0 */
cc2538_reg_t SFR_RFDATA; /**< RF Tx/Rx FIFO */
cc2538_reg_t SFR_RFERRF; /**< RF error interrupt flags */
cc2538_reg_t SFR_RFIRQF1; /**< RF interrupt flags */
cc2538_reg_t SFR_RFIRQF0; /**< RF interrupt flags */
cc2538_reg_t SFR_RFST; /**< RF CSMA-CA/strobe processor */
} cc2538_rfcore_t;
#define RFCORE ( (cc2538_rfcore_t*)0x40088580 ) /**< RF Core instance */
/** @brief RF Core opcodes */
enum {
DECZ = 0xc5, /**< Decrement Z */
DECY = 0xc4, /**< Decrement Y */
DECX = 0xc3, /**< Decrement X */
INCZ = 0xc2, /**< Increment Z */
INCY = 0xc1, /**< Increment Y */
INCX = 0xc0, /**< Increment X */
INCMAXY = 0xc8, /**< Increment Y not greater than M. | M (M = 0-7) */
RANDXY = 0xbd, /**< Load random value into X. */
INT = 0xba, /**< Interrupt */
WAITX = 0xbc, /**< Wait for X MAC timer overflows */
SETCMP1 = 0xbe, /**< Set the compare value of the MAC timer to the current timer value. */
WAIT_W = 0x80, /**< Wait for W MAC timer overflows | W (W = 0-31) */
WEVENT1 = 0xb8, /**< Wait until MAC timer event 1 */
WEVENT2 = 0xb9, /**< Wait until MAC timer event 2 */
LABEL = 0xbb, /**< Set loop label */
RPT_C = 0xa0, /**< Conditional repeat | N | C (N = 0, 8; C = 0-7) */
SKIP_S_C = 0x00, /**< Conditional skip instruction | S | N | C */
STOP = 0xd2, /**< Stop program execution */
SNOP = 0xd0, /**< No operation */
SRXON = 0xd3, /**< Enable and calibrate frequency synthesizer for RX */
STXON = 0xd9, /**< Enable TX after calibration */
STXONCCA = 0xda, /**< Enable calibration and TX if CCA indicates a clear channel */
SSAMPLECCA = 0xdb, /**< Sample the current CCA value to SAMPLED_CCA */
SRFOFF = 0xdf, /**< Disable RX or TX and frequency synthesizer. */
SFLUSHRX = 0xdd, /**< Flush RX FIFO buffer and reset demodulator */
SFLUSHTX = 0xde, /**< Flush TX FIFO buffer */
SACK = 0xd6, /**< Send acknowledge frame with pending field cleared */
SACKPEND = 0xd7, /**< Send acknowledge frame with the pending field set */
SNACK = 0xd8, /**< Abort sending of acknowledge frame */
SRXMASKBITSET = 0xd4, /**< Set bit in RXENABLE register */
SRXMASKBITCLR = 0xd5, /**< Clear bit in RXENABLE register */
ISSTOP = 0xe2, /**< Stop program execution */
ISSTART = 0xe1, /**< Start program execution */
ISRXON = 0xe3, /**< Enable and calibrate frequency synthesizer for RX */
ISRXMASKBITSET = 0xe4, /**< Set bit in RXENABLE */
ISRXMASKBITCLR = 0xe5, /**< Clear bit in RXENABLE */
ISTXON = 0xe9, /**< Enable TX after calibration */
ISTXONCCA = 0xea, /**< Enable calibration and TX if CCA indicates a clear channel */
ISSAMPLECCA = 0xeb, /**< Sample the current CCA value to SAMPLED_CCA */
ISRFOFF = 0xef, /**< Disable RX or TX, and the frequency synthesizer. */
ISFLUSHRX = 0xed, /**< Flush RX FIFO buffer and reset demodulator */
ISFLUSHTX = 0xee, /**< Flush TX FIFO buffer */
ISACK = 0xe6, /**< Send acknowledge frame with the pending field cleared */
ISACKPEND = 0xe7, /**< Send acknowledge frame with the pending field set */
ISNACK = 0xe8, /**< Abort sending of acknowledge frame */
ISCLEAR = 0xff, /**< Clear CSP program memory, reset program counter */
};
#endif /* CC2538_RFCORE_H */
/** @} */
/** @} */
/** @} */

View File

@ -0,0 +1,62 @@
/*
* 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 soc-adc.h
* @brief CC2538 SOC ADC interface
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef CC2538_SOC_ADC_H
#define CC2538_SOC_ADC_H
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief SOC ADC component registers
*/
typedef struct {
union {
cc2538_reg_t ADCCON1; /**< ADC Control Register 1 */
struct {
cc2538_reg_t RESERVED2 : 2; /**< Reserved bits */
cc2538_reg_t RCTRL : 2; /**< Random number generator control */
cc2538_reg_t STSEL : 2; /**< Start select */
cc2538_reg_t ST : 1; /**< Start conversion */
cc2538_reg_t EOC : 1; /**< End of conversion */
cc2538_reg_t RESERVED1 : 24; /**< Reserved bits */
} ADCCON1bits;
};
cc2538_reg_t ADCCON2; /**< ADC Control Register 2 */
cc2538_reg_t ADCCON3; /**< ADC Control Register 3 */
cc2538_reg_t ADCL; /**< Least-significant part of ADC conversion result. */
cc2538_reg_t ADCH; /**< Most-significant part of ADC conversion result. */
cc2538_reg_t RNDL; /**< Random-number-generator data; low byte. */
cc2538_reg_t RNDH; /**< Random-number-generator data; high byte. */
cc2538_reg_t RESERVED[2]; /**< Reserved bytes */
cc2538_reg_t CMPCTL; /**< Analog comparator control and status register. */
} cc2538_soc_adc_t;
#define SOC_ADC ( (cc2538_soc_adc_t*)0x400d7000 ) /**< One and only instance of the SOC ADC component */
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* CC2538_SOC_ADC_H */
/** @} */

View File

@ -0,0 +1,145 @@
/*
* 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 sys-ctrl.h
* @brief CC2538 System Control interface
*
* @author Ian Martin <ian@locicontrols.com>
*/
#ifndef CC2538_SYS_CTRL_H
#define CC2538_SYS_CTRL_H
#include "cc2538.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief System Control component registers
*/
typedef struct {
union {
cc2538_reg_t CLOCK_CTRL; /**< Clock control register */
struct {
cc2538_reg_t SYS_DIV : 3; /**< System clock rate setting */
cc2538_reg_t RESERVED1 : 5; /**< Reserved bits */
cc2538_reg_t IO_DIV : 3; /**< I/O clock rate setting */
cc2538_reg_t RESERVED2 : 5; /**< Reserved bits */
cc2538_reg_t OSC : 1; /**< System clock oscillator selection */
cc2538_reg_t OSC_PD : 1; /**< Oscillator power-down */
cc2538_reg_t RESERVED3 : 3; /**< Reserved bits */
cc2538_reg_t AMP_DET : 1; /**< Amplitude detector of XOSC during power up */
cc2538_reg_t RESERVED4 : 2; /**< Reserved bits */
cc2538_reg_t OSC32K : 1; /**< 32-kHz clock oscillator selection */
cc2538_reg_t OSC32K_CADIS : 1; /**< Disable calibration 32-kHz RC oscillator */
cc2538_reg_t RESERVED5 : 6; /**< Reserved bits */
} CLOCK_CTRLbits;
};
union {
cc2538_reg_t CLOCK_STA; /**< Clock status register */
struct {
cc2538_reg_t SYS_DIV : 3; /**< Current functional frequency for system clock */
cc2538_reg_t RESERVED6 : 5; /**< Reserved bits */
cc2538_reg_t IO_DIV : 3; /**< Current functional frequency for IO_CLK */
cc2538_reg_t RESERVED7 : 5; /**< Reserved bits */
cc2538_reg_t OSC : 1; /**< Current clock source selected */
cc2538_reg_t OSC_PD : 1; /**< Oscillator power-down */
cc2538_reg_t HSOSC_STB : 1; /**< HSOSC stable status */
cc2538_reg_t XOSC_STB : 1; /**< XOSC stable status */
cc2538_reg_t SOURCE_CHANGE : 1; /**< System clock source change */
cc2538_reg_t RESERVED8 : 1; /**< Reserved bits */
cc2538_reg_t RST : 2; /**< Last source of reset */
cc2538_reg_t OSC32K : 1; /**< Current 32-kHz clock oscillator selected */
cc2538_reg_t OSC32K_CALDIS : 1; /**< Disable calibration 32-kHz RC oscillator */
cc2538_reg_t SYNC_32K : 1; /**< 32-kHz clock source synced to undivided system clock (16 or 32 MHz) */
cc2538_reg_t RESERVED9 : 5; /**< Reserved bits */
} CLOCK_STAbits;
};
cc2538_reg_t RCGCGPT; /**< Module clocks for GPT[3:0] when the CPU is in active (run) mode */
cc2538_reg_t SCGCGPT; /**< Module clocks for GPT[3:0] when the CPU is in sleep mode */
cc2538_reg_t DCGCGPT; /**< Module clocks for GPT[3:0] when the CPU is in PM0 */
cc2538_reg_t SRGPT; /**< Reset for GPT[3:0]. */
cc2538_reg_t RCGCSSI; /**< Module clocks for SSI[1:0] when the CPU is in active (run) mode */
cc2538_reg_t SCGCSSI; /**< Module clocks for SSI[1:0] when the CPU is insSleep mode */
cc2538_reg_t DCGCSSI; /**< Module clocks for SSI[1:0] when the CPU is in PM0 */
cc2538_reg_t SRSSI; /**< Reset for SSI[1:0]. */
union {
cc2538_reg_t RCGCUART; /**< Module clocks for UART[1:0] when the CPU is in active (run) mode */
struct {
cc2538_reg_t UART0 : 1; /**< Enable UART0 clock in active (run) mode */
cc2538_reg_t UART1 : 1; /**< Enable UART1 clock in active (run) mode */
cc2538_reg_t RESERVED : 30; /**< Reserved bits */
} RCGCUARTbits;
};
union {
cc2538_reg_t SCGCUART; /**< Module clocks for UART[1:0] when the CPU is in sleep mode */
struct {
cc2538_reg_t UART0 : 1; /**< Enable UART0 clock in sleep mode */
cc2538_reg_t UART1 : 1; /**< Enable UART1 clock in sleep mode */
cc2538_reg_t RESERVED : 30; /**< Reserved bits */
} SCGCUARTbits;
};
union {
cc2538_reg_t DCGCUART; /**< Module clocks for UART[1:0] when the CPU is in PM0 */
struct {
cc2538_reg_t UART0 : 1; /**< Enable UART0 clock in PM0 */
cc2538_reg_t UART1 : 1; /**< Enable UART1 clock in PM0 */
cc2538_reg_t RESERVED : 30; /**< Reserved bits */
} DCGCUARTbits;
};
cc2538_reg_t SRUART; /**< Reset for UART[1:0]. */
cc2538_reg_t RCGCI2C; /**< Module clocks for I2C when the CPU is in active (run) mode */
cc2538_reg_t SCGCI2C; /**< Module clocks for I2C when the CPU is in sleep mode */
cc2538_reg_t DCGCI2C; /**< Module clocks for I2C when the CPU is in PM0 */
cc2538_reg_t SRI2C; /**< Reset for I2C. */
cc2538_reg_t RCGCSEC; /**< Module clocks for the security module when the CPU is in active (run) mode */
cc2538_reg_t SCGCSEC; /**< Module clocks for the security module when the CPU is in sleep mode */
cc2538_reg_t DCGCSEC; /**< Module clocks for the security module when the CPU is in PM0 */
cc2538_reg_t SRSEC; /**< Reset for the security module. */
cc2538_reg_t PMCTL; /**< Power mode. */
cc2538_reg_t SRCRC; /**< CRC on state retention. */
cc2538_reg_t RESERVED10[5]; /**< Reserved bits */
cc2538_reg_t PWRDBG; /**< Power debug register */
cc2538_reg_t RESERVED11[2]; /**< Reserved bits */
cc2538_reg_t CLD; /**< This register controls the clock loss detection feature. */
cc2538_reg_t RESERVED12[4]; /**< Reserved bits */
cc2538_reg_t IWE; /**< This register controls interrupt wake-up. */
cc2538_reg_t I_MAP; /**< This register selects which interrupt map to be used. */
cc2538_reg_t RESERVED13[3]; /**< Reserved bits */
cc2538_reg_t RCGCRFC; /**< This register defines the module clocks for RF CORE when the CPU is in active (run) mode */
cc2538_reg_t SCGCRFC; /**< This register defines the module clocks for RF CORE when the CPU is in sleep mode */
cc2538_reg_t DCGCRFC; /**< This register defines the module clocks for RF CORE when the CPU is in PM0 */
cc2538_reg_t EMUOVR; /**< This register defines the emulator override controls for power mode and peripheral clock gate. */
} cc2538_sys_ctrl_t;
#define SYS_CTRL ( (cc2538_sys_ctrl_t*)0x400d2000 ) /**< One and only instance of the System Control module */
/**
* @brief Compute the current system clock frequency based on the SYS_CTRL register states
*/
#define sys_clock_freq() ( (SYS_CTRL->CLOCK_CTRLbits.OSC? RCOSC16M_FREQ : XOSC32M_FREQ) >> SYS_CTRL->CLOCK_CTRLbits.SYS_DIV )
#ifdef __cplusplus
} /* end extern "C" */
#endif
#endif /* CC2538_SYS_CTRL_H */
/** @} */

View File

@ -7,7 +7,7 @@
*/
/**
* @ingroup cpu_sam3x8e
* @ingroup cpu_cc2538
* @{
*
* @file io_arch.c
@ -25,8 +25,10 @@
int io_arch_puts(char *data, int size)
{
int i = 0;
for (; i < size; i++) {
putchar(data[i]);
}
return i;
}

47
cpu/cc2538/lpm_arch.c Normal file
View File

@ -0,0 +1,47 @@
/*
* 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 lpm_arch.c
* @brief Implementation of the kernels power management interface
*
* @author Ian Martin <ian@locicontrols.com>
*
* @}
*/
#include "arch/lpm_arch.h"
void lpm_arch_init(void)
{
}
enum lpm_mode lpm_arch_set(enum lpm_mode target)
{
return 0;
}
enum lpm_mode lpm_arch_get(void)
{
return 0;
}
void lpm_arch_awake(void)
{
}
void lpm_arch_begin_awake(void)
{
}
void lpm_arch_end_awake(void)
{
}

View File

@ -0,0 +1 @@
include $(RIOTBASE)/Makefile.base

48
cpu/cc2538/periph/cpuid.c Normal file
View File

@ -0,0 +1,48 @@
/*
* 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 cpuid.c
* @brief CPU-ID driver implementation
*
* The CC2538 provides a 64-bit unique identifier, that is unique for each shipped unit.
*
* @author Ian Martin <ian@locicontrols.com>
*
* @}
*/
#include <string.h>
#include "cpu.h"
#include "cpu-conf.h"
#include "periph/cpuid.h"
#define BITS_PER_BYTE 8
void cpuid_get(void *id)
{
uint8_t *dest = (uint8_t *)id;
/**
* The byte-order is big-endian but the word order is little endian.
* Make some sense of it:
*/
dest[0] = IEEE_ADDR_MSWORD >> (3 * BITS_PER_BYTE);
dest[1] = IEEE_ADDR_MSWORD >> (2 * BITS_PER_BYTE);
dest[2] = IEEE_ADDR_MSWORD >> (1 * BITS_PER_BYTE);
dest[3] = IEEE_ADDR_MSWORD >> (0 * BITS_PER_BYTE);
dest[4] = IEEE_ADDR_LSWORD >> (3 * BITS_PER_BYTE);
dest[5] = IEEE_ADDR_LSWORD >> (2 * BITS_PER_BYTE);
dest[6] = IEEE_ADDR_LSWORD >> (1 * BITS_PER_BYTE);
dest[7] = IEEE_ADDR_LSWORD >> (0 * BITS_PER_BYTE);
}
/** @} */

658
cpu/cc2538/periph/gpio.c Normal file
View File

@ -0,0 +1,658 @@
/*
* 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 driver_periph
* @{
*
* @file gpio.c
* @brief Low-level GPIO driver implementation
*
* @author Ian Martin <ian@locicontrols.com>
*
* @}
*/
#include <stdint.h>
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "cc2538-gpio.h"
#include "ioc.h"
#include "periph/gpio.h"
#include "periph_conf.h"
/* guard file in case no GPIO devices are defined */
#if GPIO_NUMOF
/**
* @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 BIT(n) ( 1 << (n) )
/**
* @brief Checks a bit in enable_lut to determine if a GPIO is enabled
*
* @param[in] dev RIOT GPIO device number
*
* @return 0 or 1 indicating if the specified GPIO is enabled
*/
#define gpio_enabled(dev) ( (enable_lut >> (dev)) & 1 )
typedef struct {
gpio_cb_t cb; /**< callback called from GPIO interrupt */
void *arg; /**< argument passed to the callback */
} gpio_state_t;
static gpio_state_t gpio_config[GPIO_NUMOF];
const uint32_t enable_lut = 0
#if GPIO_0_EN
| BIT(0)
#endif
#if GPIO_1_EN
| BIT(1)
#endif
#if GPIO_2_EN
| BIT(2)
#endif
#if GPIO_3_EN
| BIT(3)
#endif
#if GPIO_4_EN
| BIT(4)
#endif
#if GPIO_5_EN
| BIT(5)
#endif
#if GPIO_6_EN
| BIT(6)
#endif
#if GPIO_7_EN
| BIT(7)
#endif
#if GPIO_8_EN
| BIT(8)
#endif
#if GPIO_9_EN
| BIT(9)
#endif
#if GPIO_10_EN
| BIT(10)
#endif
#if GPIO_11_EN
| BIT(11)
#endif
#if GPIO_12_EN
| BIT(12)
#endif
#if GPIO_13_EN
| BIT(13)
#endif
#if GPIO_14_EN
| BIT(14)
#endif
#if GPIO_15_EN
| BIT(15)
#endif
#if GPIO_16_EN
| BIT(16)
#endif
#if GPIO_17_EN
| BIT(17)
#endif
#if GPIO_18_EN
| BIT(18)
#endif
#if GPIO_19_EN
| BIT(19)
#endif
#if GPIO_20_EN
| BIT(20)
#endif
#if GPIO_21_EN
| BIT(21)
#endif
#if GPIO_22_EN
| BIT(22)
#endif
#if GPIO_23_EN
| BIT(23)
#endif
#if GPIO_24_EN
| BIT(24)
#endif
#if GPIO_25_EN
| BIT(25)
#endif
#if GPIO_26_EN
| BIT(26)
#endif
#if GPIO_27_EN
| BIT(27)
#endif
#if GPIO_28_EN
| BIT(28)
#endif
#if GPIO_29_EN
| BIT(29)
#endif
#if GPIO_30_EN
| BIT(30)
#endif
#if GPIO_31_EN
| BIT(31)
#endif
;
const unsigned int pin_lut[] = {
#if GPIO_0_EN
[ 0] = GPIO_0_PIN,
#endif
#if GPIO_1_EN
[ 1] = GPIO_1_PIN,
#endif
#if GPIO_2_EN
[ 2] = GPIO_2_PIN,
#endif
#if GPIO_3_EN
[ 3] = GPIO_3_PIN,
#endif
#if GPIO_4_EN
[ 4] = GPIO_4_PIN,
#endif
#if GPIO_5_EN
[ 5] = GPIO_5_PIN,
#endif
#if GPIO_6_EN
[ 6] = GPIO_6_PIN,
#endif
#if GPIO_7_EN
[ 7] = GPIO_7_PIN,
#endif
#if GPIO_8_EN
[ 8] = GPIO_8_PIN,
#endif
#if GPIO_9_EN
[ 9] = GPIO_9_PIN,
#endif
#if GPIO_10_EN
[10] = GPIO_10_PIN,
#endif
#if GPIO_11_EN
[11] = GPIO_11_PIN,
#endif
#if GPIO_12_EN
[12] = GPIO_12_PIN,
#endif
#if GPIO_13_EN
[13] = GPIO_13_PIN,
#endif
#if GPIO_14_EN
[14] = GPIO_14_PIN,
#endif
#if GPIO_15_EN
[15] = GPIO_15_PIN,
#endif
#if GPIO_16_EN
[16] = GPIO_16_PIN,
#endif
#if GPIO_17_EN
[17] = GPIO_17_PIN,
#endif
#if GPIO_18_EN
[18] = GPIO_18_PIN,
#endif
#if GPIO_19_EN
[19] = GPIO_19_PIN,
#endif
#if GPIO_20_EN
[20] = GPIO_20_PIN,
#endif
#if GPIO_21_EN
[21] = GPIO_21_PIN,
#endif
#if GPIO_22_EN
[22] = GPIO_22_PIN,
#endif
#if GPIO_23_EN
[23] = GPIO_23_PIN,
#endif
#if GPIO_24_EN
[24] = GPIO_24_PIN,
#endif
#if GPIO_25_EN
[25] = GPIO_25_PIN,
#endif
#if GPIO_26_EN
[26] = GPIO_26_PIN,
#endif
#if GPIO_27_EN
[27] = GPIO_27_PIN,
#endif
#if GPIO_28_EN
[28] = GPIO_28_PIN,
#endif
#if GPIO_29_EN
[29] = GPIO_29_PIN,
#endif
#if GPIO_30_EN
[30] = GPIO_30_PIN,
#endif
#if GPIO_31_EN
[31] = GPIO_31_PIN,
#endif
};
static const uint8_t reverse_pin_lut[] = {
#if GPIO_0_EN
[GPIO_0_PIN] = 0,
#endif
#if GPIO_1_EN
[GPIO_1_PIN] = 1,
#endif
#if GPIO_2_EN
[GPIO_2_PIN] = 2,
#endif
#if GPIO_3_EN
[GPIO_3_PIN] = 3,
#endif
#if GPIO_4_EN
[GPIO_4_PIN] = 4,
#endif
#if GPIO_5_EN
[GPIO_5_PIN] = 5,
#endif
#if GPIO_6_EN
[GPIO_6_PIN] = 6,
#endif
#if GPIO_7_EN
[GPIO_7_PIN] = 7,
#endif
#if GPIO_8_EN
[GPIO_8_PIN] = 8,
#endif
#if GPIO_9_EN
[GPIO_9_PIN] = 9,
#endif
#if GPIO_10_EN
[GPIO_10_PIN] = 10,
#endif
#if GPIO_11_EN
[GPIO_11_PIN] = 11,
#endif
#if GPIO_12_EN
[GPIO_12_PIN] = 12,
#endif
#if GPIO_13_EN
[GPIO_13_PIN] = 13,
#endif
#if GPIO_14_EN
[GPIO_14_PIN] = 14,
#endif
#if GPIO_15_EN
[GPIO_15_PIN] = 15,
#endif
#if GPIO_16_EN
[GPIO_16_PIN] = 16,
#endif
#if GPIO_17_EN
[GPIO_17_PIN] = 17,
#endif
#if GPIO_18_EN
[GPIO_18_PIN] = 18,
#endif
#if GPIO_19_EN
[GPIO_19_PIN] = 19,
#endif
#if GPIO_20_EN
[GPIO_20_PIN] = 20,
#endif
#if GPIO_21_EN
[GPIO_21_PIN] = 21,
#endif
#if GPIO_22_EN
[GPIO_22_PIN] = 22,
#endif
#if GPIO_23_EN
[GPIO_23_PIN] = 23,
#endif
#if GPIO_24_EN
[GPIO_24_PIN] = 24,
#endif
#if GPIO_25_EN
[GPIO_25_PIN] = 25,
#endif
#if GPIO_26_EN
[GPIO_26_PIN] = 26,
#endif
#if GPIO_27_EN
[GPIO_27_PIN] = 27,
#endif
#if GPIO_28_EN
[GPIO_28_PIN] = 28,
#endif
#if GPIO_29_EN
[GPIO_29_PIN] = 29,
#endif
#if GPIO_30_EN
[GPIO_30_PIN] = 30,
#endif
#if GPIO_31_EN
[GPIO_31_PIN] = 31,
#endif
};
static const uint32_t ioc_mask_lut[] = {
[GPIO_NOPULL ] = IOC_OVERRIDE_OE,
[GPIO_PULLUP ] = IOC_OVERRIDE_OE | IOC_OVERRIDE_PUE,
[GPIO_PULLDOWN] = IOC_OVERRIDE_OE | IOC_OVERRIDE_PDE,
};
int gpio_init_out(gpio_t dev, gpio_pp_t pushpull)
{
int pin;
if (!gpio_enabled(dev)) {
return -1;
}
pin = pin_lut[dev];
gpio_software_control(pin);
gpio_dir_output(pin);
/* configure the pin's pull resistor state */
IOC_PXX_OVER[pin] = ioc_mask_lut[pushpull];
return 0;
}
int gpio_init_in(gpio_t dev, gpio_pp_t pushpull)
{
int pin;
if (!gpio_enabled(dev)) {
return -1;
}
pin = pin_lut[dev];
gpio_software_control(pin);
gpio_dir_input(pin);
/* configure the pin's pull resistor state */
IOC_PXX_OVER[pin] = ioc_mask_lut[pushpull];
return 0;
}
int gpio_init_int(gpio_t dev, gpio_pp_t pullup, gpio_flank_t flank, gpio_cb_t cb, void *arg)
{
int res, pin, irq_num;
uint32_t mask;
cc2538_gpio_t* instance;
/* Note: gpio_init_in() also checks if the gpio is enabled. */
res = gpio_init_in(dev, pullup);
if (res < 0) {
return res;
}
/* Store the callback information for later: */
gpio_config[dev].cb = cb;
gpio_config[dev].arg = arg;
pin = pin_lut[dev];
mask = GPIO_PIN_MASK(GPIO_BIT_NUM(pin));
instance = GPIO_NUM_TO_DEV(pin);
/* Enable power-up interrupts for this GPIO port: */
SYS_CTRL_IWE |= BIT(GPIO_NUM_TO_PORT_NUM(pin));
switch(flank) {
case GPIO_FALLING:
instance->IBE &= ~mask; /**< Not both edges */
instance->IEV &= ~mask; /**< Falling edge */
instance->P_EDGE_CTRL |= BIT(pin); /**< Falling edge power-up interrupt */
break;
case GPIO_RISING:
instance->IBE &= ~mask; /**< Not both edges */
instance->IEV |= mask; /**< Rising edge */
instance->P_EDGE_CTRL &= ~BIT(pin); /**< Rising edge power-up interrupt */
break;
case GPIO_BOTH:
instance->IBE = mask; /**< Both edges */
break;
}
instance->IS &= ~mask; /**< Edge triggered (as opposed to level-triggered) */
instance->IC |= mask; /**< Clear any preexisting interrupt state */
instance->PI_IEN |= BIT(pin); /**< Enable power-up interrupts for this pin */
/* Set interrupt priority for the whole GPIO port: */
irq_num = GPIO_PORT_A_IRQn + GPIO_NUM_TO_PORT_NUM(pin);
NVIC_SetPriority(irq_num, GPIO_IRQ_PRIO);
/* Enable interrupts for the whole GPIO port: */
NVIC_EnableIRQ(irq_num);
/* Enable interrupts for the specific pin: */
instance->IE |= mask;
return 0;
}
void gpio_irq_enable(gpio_t dev)
{
if (gpio_enabled(dev)) {
int pin = pin_lut[dev];
GPIO_NUM_TO_DEV(pin)->IE |= GPIO_PIN_MASK(GPIO_BIT_NUM(pin));
}
}
void gpio_irq_disable(gpio_t dev)
{
if (gpio_enabled(dev)) {
int pin = pin_lut[dev];
GPIO_NUM_TO_DEV(pin)->IE &= ~GPIO_PIN_MASK(GPIO_BIT_NUM(pin));
}
}
int gpio_read(gpio_t dev)
{
int pin;
if (!gpio_enabled(dev)) {
return -1;
}
pin = pin_lut[dev];
return (GPIO_NUM_TO_DEV(pin)->DATA >> GPIO_BIT_NUM(pin)) & 1;
}
void gpio_set(gpio_t dev)
{
int pin;
if (!gpio_enabled(dev)) {
return;
}
pin = pin_lut[dev];
GPIO_NUM_TO_DEV(pin)->DATA |= GPIO_PIN_MASK(GPIO_BIT_NUM(pin));
}
void gpio_clear(gpio_t dev)
{
int pin;
if (!gpio_enabled(dev)) {
return;
}
pin = pin_lut[dev];
GPIO_NUM_TO_DEV(pin)->DATA &= ~GPIO_PIN_MASK(GPIO_BIT_NUM(pin));
}
void gpio_toggle(gpio_t dev)
{
if (gpio_read(dev)) {
gpio_clear(dev);
}
else {
gpio_set(dev);
}
}
void gpio_write(gpio_t dev, int value)
{
if (value) {
gpio_set(dev);
}
else {
gpio_clear(dev);
}
}
/** @brief Interrupt service routine for Port A */
__attribute__((naked))
void gpio_port_a_isr(void)
{
int mis, bit;
gpio_state_t* state;
ISR_ENTER();
asm("push {r4-r5}");
/* Latch and clear the interrupt status early on: */
mis = GPIO_A->MIS;
GPIO_A->IC = 0x000000ff;
GPIO_A->IRQ_DETECT_ACK = 0x000000ff;
for (bit = 0; bit < GPIO_BITS_PER_PORT; bit++) {
if (mis & 1) {
state = gpio_config + reverse_pin_lut[GPIO_PXX_TO_NUM(PORT_A, bit)];
state->cb(state->arg);
}
mis >>= 1;
}
if (sched_context_switch_request) {
thread_yield();
}
asm("pop {r4-r5}");
ISR_EXIT();
}
/** @brief Interrupt service routine for Port B */
__attribute__((naked))
void gpio_port_b_isr(void)
{
int mis, bit;
gpio_state_t* state;
ISR_ENTER();
asm("push {r4-r5}");
/* Latch and clear the interrupt status early on: */
mis = GPIO_B->MIS;
GPIO_B->IC = 0x000000ff;
GPIO_B->IRQ_DETECT_ACK = 0x0000ff00;
for (bit = 0; bit < GPIO_BITS_PER_PORT; bit++) {
if (mis & 1) {
state = gpio_config + reverse_pin_lut[GPIO_PXX_TO_NUM(PORT_B, bit)];
state->cb(state->arg);
}
mis >>= 1;
}
if (sched_context_switch_request) {
thread_yield();
}
asm("pop {r4-r5}");
ISR_EXIT();
}
/** @brief Interrupt service routine for Port C */
__attribute__((naked))
void gpio_port_c_isr(void)
{
int mis, bit;
gpio_state_t* state;
ISR_ENTER();
asm("push {r4-r5}");
/* Latch and clear the interrupt status early on: */
mis = GPIO_C->MIS;
GPIO_C->IC = 0x000000ff;
GPIO_C->IRQ_DETECT_ACK = 0x00ff0000;
for (bit = 0; bit < GPIO_BITS_PER_PORT; bit++) {
if (mis & 1) {
state = gpio_config + reverse_pin_lut[GPIO_PXX_TO_NUM(PORT_C, bit)];
state->cb(state->arg);
}
mis >>= 1;
}
if (sched_context_switch_request) {
thread_yield();
}
asm("pop {r4-r5}");
ISR_EXIT();
}
/** @brief Interrupt service routine for Port D */
__attribute__((naked))
void gpio_port_d_isr(void)
{
int mis, bit;
gpio_state_t* state;
ISR_ENTER();
asm("push {r4-r5}");
/* Latch and clear the interrupt status early on: */
mis = GPIO_D->MIS;
GPIO_D->IC = 0x000000ff;
GPIO_D->IRQ_DETECT_ACK = 0xff000000;
for (bit = 0; bit < GPIO_BITS_PER_PORT; bit++) {
if (mis & 1) {
state = gpio_config + reverse_pin_lut[GPIO_PXX_TO_NUM(PORT_D, bit)];
state->cb(state->arg);
}
mis >>= 1;
}
if (sched_context_switch_request) {
thread_yield();
}
asm("pop {r4-r5}");
ISR_EXIT();
}
#endif /* GPIO_NUMOF */

106
cpu/cc2538/periph/random.c Normal file
View File

@ -0,0 +1,106 @@
/*
* 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 driver_periph
* @{
*
* @file random.c
* @brief Low-level random number generator driver implementation
*
* @author Ian Martin <ian@locicontrols.com>
*
* @}
*/
#include <stdint.h>
#include "cpu.h"
#include "rfcore.h"
#include "soc-adc.h"
#include "periph_conf.h"
#include "periph/random.h"
/* only compile this driver if enabled in the board's periph_conf.h */
#if RANDOM_NUMOF
void random_init(void)
{
uint16_t seed = 0;
int i;
/* Make sure the RNG is on */
SOC_ADC->ADCCON1bits.RCTRL = 0;
/* Enable clock for the RF Core */
SYS_CTRL_RCGCRFC = 1;
/* Wait for the clock ungating to take effect */
while (SYS_CTRL_RCGCRFC != 1);
/* Infinite RX - FRMCTRL0[3:2] = 10. This will mess with radio operation */
RFCORE_XREG_FRMCTRL0 = 0x00000008;
/* Turn RF on */
RFCORE_SFR_RFST = ISRXON;
/*
* Wait until "the chip has been in RX long enough for the transients to
* have died out. A convenient way to do this is to wait for the RSSI-valid
* signal to go high."
*/
while (!RFCORE->XREG_RSSISTATbits.RSSI_VALID);
/*
* Form the seed by concatenating bits from IF_ADC in the RF receive path.
* Keep sampling until we have read at least 16 bits AND the seed is valid
*
* Invalid seeds are 0 and 0x8003 and should not be used.
*/
for (i = 0; (i < 8) || (seed == 0) || (seed == 0x8003); i++) {
seed <<= 2;
seed ^= RFCORE->XREG_RFRND;
}
/* Seed the high byte first: */
SOC_ADC_RNDL = (seed >> 8) & 0xff;
SOC_ADC_RNDL = seed & 0xff;
/* Turn RF off: */
RFCORE_SFR_RFST = ISRFOFF;
random_poweron();
}
int random_read(char *buf, unsigned int num)
{
int count;
for (count = 0; count < num; ) {
/* Clock the RNG LSFR once: */
SOC_ADC->ADCCON1bits.RCTRL = 1;
/* Read up to 2 bytes of random data: */
buf[count++] = SOC_ADC_RNDL;
if (count >= num) break;
buf[count++] = SOC_ADC_RNDH;
}
return count;
}
void random_poweron(void)
{
}
void random_poweroff(void)
{
}
#endif /* RANDOM_NUMOF */

506
cpu/cc2538/periph/timer.c Normal file
View File

@ -0,0 +1,506 @@
/*
* 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 driver_periph
* @{
*
* @file timer.c
* @brief Low-level timer driver implementation for the CC2538 CPU
*
* @author Ian Martin <ian@locicontrols.com>
*
* @}
*/
#include <stdlib.h>
#include <stdio.h>
#include "board.h"
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "gptimer.h"
#include "periph/timer.h"
#include "periph_conf.h"
#define USEC_PER_SEC 1000000 /**< Conversion factor between seconds and microseconds */
typedef struct {
void (*cb)(int);
} timer_conf_t;
/**
* @brief Timer state memory
*/
timer_conf_t config[TIMER_NUMOF];
/**
* @brief Setup the given timer
*
*/
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
{
cc2538_gptimer_t *gptimer;
unsigned int gptimer_num;
/* select the timer and enable the timer specific peripheral clocks */
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
gptimer = TIMER_0_DEV;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
gptimer = TIMER_1_DEV;
break;
#endif
#if TIMER_2_EN
case TIMER_2:
gptimer = TIMER_2_DEV;
break;
#endif
#if TIMER_3_EN
case TIMER_3:
gptimer = TIMER_3_DEV;
break;
#endif
case TIMER_UNDEFINED:
default:
return -1;
}
gptimer_num = ((uintptr_t)gptimer - (uintptr_t)GPTIMER0) / 0x1000;
/* Save the callback function: */
config[dev].cb = callback;
/* Enable the clock for this timer: */
SYS_CTRL_RCGCGPT |= (1 << gptimer_num);
/* Disable this timer before configuring it: */
gptimer->CTL = 0;
gptimer->CFG = GPTMCFG_16_BIT_TIMER;
gptimer->TAMR = GPTIMER_PERIODIC_MODE;
gptimer->TAMRbits.TACDIR = 1; /**< Count up */
/* Set the prescale register for the desired frequency: */
gptimer->TAPR = RCOSC16M_FREQ / (ticks_per_us * USEC_PER_SEC) - 1;
/* Enable interrupts for given timer: */
timer_irq_enable(dev);
/* Enable the timer: */
gptimer->CTLbits.TAEN = 1;
return 0;
}
int timer_set(tim_t dev, int channel, unsigned int timeout)
{
return timer_set_absolute(dev, channel, timer_read(dev) + timeout);
}
int timer_set_absolute(tim_t dev, int channel, unsigned int value)
{
cc2538_gptimer_t *gptimer;
/* get timer base register address */
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
gptimer = TIMER_0_DEV;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
gptimer = TIMER_1_DEV;
break;
#endif
#if TIMER_2_EN
case TIMER_2:
gptimer = TIMER_2_DEV;
break;
#endif
#if TIMER_3_EN
case TIMER_3:
gptimer = TIMER_3_DEV;
break;
#endif
case TIMER_UNDEFINED:
default:
return -1;
}
/* set timeout value */
switch (channel) {
case 0:
gptimer->TAILR = value;
break;
case 1:
gptimer->TBILR = value;
break;
default:
return -1;
}
return 1;
}
int timer_clear(tim_t dev, int channel)
{
cc2538_gptimer_t *gptimer;
/* get timer base register address */
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
gptimer = TIMER_0_DEV;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
gptimer = TIMER_1_DEV;
break;
#endif
#if TIMER_2_EN
case TIMER_2:
gptimer = TIMER_2_DEV;
break;
#endif
#if TIMER_3_EN
case TIMER_3:
gptimer = TIMER_3_DEV;
break;
#endif
case TIMER_UNDEFINED:
default:
return -1;
}
switch (channel) {
case 0:
gptimer->CTLbits.TAEN = 0;
break;
case 1:
gptimer->CTLbits.TBEN = 0;
break;
default:
return -1;
}
return 1;
}
/*
* The timer channels 1 and 2 are configured to run with the same speed and
* have the same value (they run in parallel), so only on of them is returned.
*/
unsigned int timer_read(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
return TIMER_0_DEV->TAR;
#endif
#if TIMER_1_EN
case TIMER_1:
return TIMER_1_DEV->TAR;
#endif
#if TIMER_2_EN
case TIMER_2:
return TIMER_2_DEV->TAR;
#endif
#if TIMER_3_EN
case TIMER_3:
return TIMER_3_DEV->TAR;
#endif
case TIMER_UNDEFINED:
default:
return 0;
}
}
/*
* For stopping the counting of all channels.
*/
void timer_stop(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
TIMER_0_DEV->CTLbits.TAEN = 0;
TIMER_0_DEV->CTLbits.TBEN = 0;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
TIMER_1_DEV->CTLbits.TAEN = 0;
TIMER_1_DEV->CTLbits.TBEN = 0;
break;
#endif
#if TIMER_2_EN
case TIMER_2:
TIMER_2_DEV->CTLbits.TAEN = 0;
TIMER_2_DEV->CTLbits.TBEN = 0;
break;
#endif
#if TIMER_3_EN
case TIMER_3:
TIMER_3_DEV->CTLbits.TAEN = 0;
TIMER_3_DEV->CTLbits.TBEN = 0;
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_start(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
TIMER_0_DEV->CTLbits.TAEN = 1;
TIMER_0_DEV->CTLbits.TBEN = 1;
break;
#endif
#if TIMER_1_EN
case TIMER_1:
TIMER_1_DEV->CTLbits.TAEN = 1;
TIMER_1_DEV->CTLbits.TBEN = 1;
break;
#endif
#if TIMER_2_EN
case TIMER_2:
TIMER_2_DEV->CTLbits.TAEN = 1;
TIMER_2_DEV->CTLbits.TBEN = 1;
break;
#endif
#if TIMER_3_EN
case TIMER_3:
TIMER_3_DEV->CTLbits.TAEN = 1;
TIMER_3_DEV->CTLbits.TBEN = 1;
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_irq_enable(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
NVIC_SetPriority(TIMER_0_IRQn_1, TIMER_IRQ_PRIO);
NVIC_SetPriority(TIMER_0_IRQn_2, TIMER_IRQ_PRIO);
NVIC_EnableIRQ(TIMER_0_IRQn_1);
NVIC_EnableIRQ(TIMER_0_IRQn_2);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
NVIC_SetPriority(TIMER_1_IRQn_1, TIMER_IRQ_PRIO);
NVIC_SetPriority(TIMER_1_IRQn_2, TIMER_IRQ_PRIO);
NVIC_EnableIRQ(TIMER_1_IRQn_1);
NVIC_EnableIRQ(TIMER_1_IRQn_2);
break;
#endif
#if TIMER_2_EN
case TIMER_2:
NVIC_SetPriority(TIMER_2_IRQn_1, TIMER_IRQ_PRIO);
NVIC_SetPriority(TIMER_2_IRQn_2, TIMER_IRQ_PRIO);
NVIC_EnableIRQ(TIMER_2_IRQn_1);
NVIC_EnableIRQ(TIMER_2_IRQn_2);
break;
#endif
#if TIMER_3_EN
case TIMER_3:
NVIC_SetPriority(TIMER_3_IRQn_1, TIMER_IRQ_PRIO);
NVIC_SetPriority(TIMER_3_IRQn_2, TIMER_IRQ_PRIO);
NVIC_EnableIRQ(TIMER_3_IRQn_1);
NVIC_EnableIRQ(TIMER_3_IRQn_2);
break;
#endif
case TIMER_UNDEFINED:
default:
return;
}
}
void timer_irq_disable(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
NVIC_DisableIRQ(TIMER_0_IRQn_1);
NVIC_DisableIRQ(TIMER_0_IRQn_2);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
NVIC_DisableIRQ(TIMER_1_IRQn_1);
NVIC_DisableIRQ(TIMER_1_IRQn_2);
break;
#endif
#if TIMER_2_EN
case TIMER_2:
NVIC_DisableIRQ(TIMER_2_IRQn_1);
NVIC_DisableIRQ(TIMER_2_IRQn_2);
break;
#endif
#if TIMER_3_EN
case TIMER_3:
NVIC_DisableIRQ(TIMER_3_IRQn_1);
NVIC_DisableIRQ(TIMER_3_IRQn_2);
break;
#endif
case TIMER_UNDEFINED:
default:
return;
}
}
void timer_reset(tim_t dev)
{
timer_set_absolute(dev, 0, 0);
timer_set_absolute(dev, 1, 0);
}
#if TIMER_0_EN
__attribute__((naked))
void isr_timer0_chan0(void)
{
ISR_ENTER();
if (config[0].cb != NULL) config[0].cb(0);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked))
void isr_timer0_chan1(void)
{
ISR_ENTER();
if (config[0].cb != NULL) config[0].cb(1);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
#endif /* TIMER_0_EN */
#if TIMER_1_EN
__attribute__((naked))
void isr_timer1_chan0(void)
{
ISR_ENTER();
if (config[1].cb != NULL) config[1].cb(0);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked))
void isr_timer1_chan1(void)
{
ISR_ENTER();
if (config[1].cb != NULL) config[1].cb(1);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
#endif /* TIMER_1_EN */
#if TIMER_2_EN
__attribute__((naked))
void isr_timer2_chan0(void)
{
ISR_ENTER();
if (config[2].cb != NULL) config[2].cb(0);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked))
void isr_timer2_chan1(void)
{
ISR_ENTER();
if (config[2].cb != NULL) config[2].cb(1);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
#endif /* TIMER_2_EN */
#if TIMER_3_EN
__attribute__((naked))
void isr_timer3_chan0(void)
{
ISR_ENTER();
if (config[3].cb != NULL) config[3].cb(0);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
__attribute__((naked))
void isr_timer3_chan1(void)
{
ISR_ENTER();
if (config[3].cb != NULL) config[3].cb(1);
if (sched_context_switch_request) {
thread_yield();
}
ISR_EXIT();
}
#endif /* TIMER_3_EN */

446
cpu/cc2538/periph/uart.c Normal file
View File

@ -0,0 +1,446 @@
/*
* 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 driver_periph
* @{
*
* @file uart.c
* @brief Low-level UART driver implementation
*
* @author Ian Martin <ian@locicontrols.com>
*
* @}
*/
#include <stddef.h>
#include "board.h"
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "cc2538-gpio.h"
#include "cc2538-uart.h"
#include "ioc.h"
#include "sys-ctrl.h"
#include "periph/uart.h"
#include "periph_conf.h"
/* guard file in case no UART device was specified */
#if UART_NUMOF
#undef BIT
#define BIT(n) ( 1 << (n) )
#define UART_WORD_LENGTH 8
enum {
FIFO_LEVEL_1_8TH = 0,
FIFO_LEVEL_2_8TH = 1,
FIFO_LEVEL_4_8TH = 2,
FIFO_LEVEL_6_8TH = 3,
FIFO_LEVEL_7_8TH = 4,
};
/* Bit masks for the UART Masked Interrupt Status (MIS) Register: */
#define OEMIS BIT(10) /**< UART overrun error masked status */
#define BEMIS BIT( 9) /**< UART break error masked status */
#define FEMIS BIT( 7) /**< UART framing error masked status */
#define RTMIS BIT( 6) /**< UART RX time-out masked status */
#define RXMIS BIT( 4) /**< UART RX masked interrupt status */
#define UART_CTL_HSE_VALUE 0
#define DIVFRAC_NUM_BITS 6
#define DIVFRAC_MASK ( (1 << DIVFRAC_NUM_BITS) - 1 )
/** @brief Indicates if there are bytes available in the UART0 receive FIFO */
#define uart0_rx_avail() ( UART0->FRbits.RXFE == 0 )
/** @brief Indicates if there are bytes available in the UART1 receive FIFO */
#define uart1_rx_avail() ( UART1->FRbits.RXFE == 0 )
/** @brief Read one byte from the UART0 receive FIFO */
#define uart0_read() ( UART0->DR )
/** @brief Read one byte from the UART1 receive FIFO */
#define uart1_read() ( UART1->DR )
/*---------------------------------------------------------------------------*/
/**
* @brief Each UART device has to store two callbacks.
*/
typedef struct {
uart_rx_cb_t rx_cb;
uart_tx_cb_t tx_cb;
void *arg;
} uart_conf_t;
/**
* @brief Allocate memory to store the callback functions.
*/
static uart_conf_t uart_config[UART_NUMOF];
cc2538_uart_t * const UART0 = (cc2538_uart_t *)0x4000c000;
cc2538_uart_t * const UART1 = (cc2538_uart_t *)0x4000d000;
/*---------------------------------------------------------------------------*/
static void reset(cc2538_uart_t *u)
{
/* Make sure the UART is disabled before trying to configure it */
u->CTL = 0;
u->CTLbits.RXE = 1;
u->CTLbits.TXE = 1;
u->CTLbits.HSE = UART_CTL_HSE_VALUE;
/* Clear error status */
u->ECR = 0xFF;
/* Flush FIFOs by clearing LCHR.FEN */
u->LCRHbits.FEN = 0;
/* Restore LCHR configuration */
u->LCRHbits.FEN = 1;
/* UART Enable */
u->CTLbits.UARTEN = 1;
}
/*---------------------------------------------------------------------------*/
#if UART_0_EN
__attribute__((naked))
void isr_uart0(void)
{
uint_fast16_t mis;
ISR_ENTER();
asm("push {r4}");
/* Store the current MIS and clear all flags early, except the RTM flag.
* This will clear itself when we read out the entire FIFO contents */
mis = UART_0_DEV->MIS;
UART_0_DEV->ICR = 0x0000FFBF;
while (UART_0_DEV->FRbits.RXFE == 0) {
uart_config[0].rx_cb(uart_config[0].arg, UART_0_DEV->DR);
}
if (mis & (OEMIS | BEMIS | FEMIS)) {
/* ISR triggered due to some error condition */
reset(UART_0_DEV);
}
if (sched_context_switch_request) {
thread_yield();
}
asm("pop {r4}");
ISR_EXIT();
}
#endif /* UART_0_EN */
#if UART_1_EN
__attribute__((naked))
void isr_uart1(void)
{
uint_fast16_t mis;
ISR_ENTER();
asm("push {r4}");
/* Store the current MIS and clear all flags early, except the RTM flag.
* This will clear itself when we read out the entire FIFO contents */
mis = UART_1_DEV->MIS;
UART_1_DEV->ICR = 0x0000FFBF;
while (UART_1_DEV->FRbits.RXFE == 0) {
uart_config[1].rx_cb(uart_config[1].arg, UART_1_DEV->DR);
}
if (mis & (OEMIS | BEMIS | FEMIS)) {
/* ISR triggered due to some error condition */
reset(UART_1_DEV);
}
if (sched_context_switch_request) {
thread_yield();
}
asm("pop {r4}");
ISR_EXIT();
}
#endif /* UART_1_EN */
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, uart_tx_cb_t tx_cb, void *arg)
{
/* initialize basic functionality */
int res = uart_init_blocking(uart, baudrate);
if (res != 0) {
return res;
}
/* register callbacks */
uart_config[uart].rx_cb = rx_cb;
uart_config[uart].tx_cb = tx_cb;
uart_config[uart].arg = arg;
/* configure interrupts and enable RX interrupt */
switch (uart) {
#if UART_0_EN
case UART_0:
NVIC_SetPriority(UART0_IRQn, UART_IRQ_PRIO);
NVIC_EnableIRQ(UART0_IRQn);
break;
#endif
#if UART_1_EN
case UART_1:
NVIC_SetPriority(UART1_IRQn, UART_IRQ_PRIO);
NVIC_EnableIRQ(UART1_IRQn);
break;
#endif
}
return 0;
}
int uart_init_blocking(uart_t uart, uint32_t baudrate)
{
cc2538_uart_t *u;
unsigned int uart_num;
uint32_t divisor;
switch (uart) {
#if UART_0_EN
case UART_0:
u = UART_0_DEV;
/* Run on SYS_DIV */
u->CC = 0;
/*
* Select the UARTx RX pin by writing to the IOC_UARTRXD_UARTn register
*/
IOC_UARTRXD_UART0 = UART_0_RX_PIN;
/*
* Pad Control for the TX pin:
* - Set function to UARTn TX
* - Output Enable
*/
IOC_PXX_SEL[UART_0_TX_PIN] = UART0_TXD;
IOC_PXX_OVER[UART_0_TX_PIN] = IOC_OVERRIDE_OE;
/* Set RX and TX pins to peripheral mode */
gpio_hardware_control(UART_0_TX_PIN);
gpio_hardware_control(UART_0_RX_PIN);
break;
#endif
#if UART_1_EN
case UART_1:
u = UART_1_DEV;
/* Run on SYS_DIV */
u->CC = 0;
/*
* Select the UARTx RX pin by writing to the IOC_UARTRXD_UARTn register
*/
IOC_UARTRXD_UART1 = UART_1_RX_PIN;
/*
* Pad Control for the TX pin:
* - Set function to UARTn TX
* - Output Enable
*/
IOC_PXX_SEL[UART_1_TX_PIN] = UART1_TXD;
IOC_PXX_OVER[UART_1_TX_PIN] = IOC_OVERRIDE_OE;
/* Set RX and TX pins to peripheral mode */
gpio_hardware_control(UART_1_TX_PIN);
gpio_hardware_control(UART_1_RX_PIN);
#if ( defined(UART_1_RTS_PORT) && defined(UART_1_RTS_PIN) )
IOC_PXX_SEL[UART_1_RTS_PIN] = UART1_RTS;
gpio_hardware_control(UART_1_RTS_PIN);
IOC_PXX_OVER[UART_1_RTS_PIN] = IOC_OVERRIDE_OE;
u->CTLbits.RTSEN = 1;
#endif
#if ( defined(UART_1_CTS_PORT) && defined(UART_1_CTS_PIN) )
IOC_UARTCTS_UART1 = UART_1_CTS_PIN;
gpio_hardware_control(UART_1_CTS_PIN);
IOC_PXX_OVER[UART_1_CTS_PIN] = IOC_OVERRIDE_DIS;
u->CTLbits.CTSEN = 1;
#endif
break;
#endif
default:
return -1;
}
/* Enable clock for the UART while Running, in Sleep and Deep Sleep */
uart_num = ( (uintptr_t)u - (uintptr_t)UART0 ) / 0x1000;
SYS_CTRL_RCGCUART |= (1 << uart_num);
SYS_CTRL_SCGCUART |= (1 << uart_num);
SYS_CTRL_DCGCUART |= (1 << uart_num);
/*
* UART Interrupt Masks:
* Acknowledge RX and RX Timeout
* Acknowledge Framing, Overrun and Break Errors
*/
u->IM = 0;
u->IMbits.RXIM = 1; /**< UART receive interrupt mask */
u->IMbits.RTIM = 1; /**< UART receive time-out interrupt mask */
u->IMbits.OEIM = 1; /**< UART overrun error interrupt mask */
u->IMbits.BEIM = 1; /**< UART break error interrupt mask */
u->IMbits.FEIM = 1; /**< UART framing error interrupt mask */
/* Set FIFO interrupt levels: */
u->IFLSbits.RXIFLSEL = FIFO_LEVEL_1_8TH;
u->IFLSbits.TXIFLSEL = FIFO_LEVEL_4_8TH;
/* Make sure the UART is disabled before trying to configure it */
u->CTL = 0;
u->CTLbits.RXE = 1;
u->CTLbits.TXE = 1;
u->CTLbits.HSE = UART_CTL_HSE_VALUE;
/* Set the divisor for the baud rate generator */
divisor = sys_clock_freq();
divisor <<= UART_CTL_HSE_VALUE + 2;
divisor /= baudrate;
u->IBRD = divisor >> DIVFRAC_NUM_BITS;
u->FBRD = divisor & DIVFRAC_MASK;
/* Configure line control for 8-bit, no parity, 1 stop bit and enable */
u->LCRH = 0;
u->LCRHbits.WLEN = UART_WORD_LENGTH - 5;
u->LCRHbits.FEN = 1; /**< Enable FIFOs */
u->LCRHbits.PEN = 0; /**< No parity */
/* UART Enable */
u->CTLbits.UARTEN = 1;
return 0;
}
void uart_tx_begin(uart_t uart)
{
}
void uart_tx_end(uart_t uart)
{
}
int uart_write(uart_t uart, char data)
{
cc2538_uart_t *u;
switch (uart) {
#if UART_0_EN
case UART_0:
u = UART_0_DEV;
break;
#endif
#if UART_1_EN
case UART_1:
u = UART_1_DEV;
break;
#endif
default:
return -1;
}
if (u->FRbits.TXFF) {
return 0;
}
u->DR = data;
return 1;
}
int uart_read_blocking(uart_t uart, char *data)
{
cc2538_uart_t *u;
switch (uart) {
#if UART_0_EN
case UART_0:
u = UART_0_DEV;
break;
#endif
#if UART_1_EN
case UART_1:
u = UART_1_DEV;
break;
#endif
default:
return -1;
}
while (u->FRbits.RXFE);
*data = u->DR;
return 1;
}
int uart_write_blocking(uart_t uart, char data)
{
cc2538_uart_t *u;
switch (uart) {
#if UART_0_EN
case UART_0:
u = UART_0_DEV;
break;
#endif
#if UART_1_EN
case UART_1:
u = UART_1_DEV;
break;
#endif
default:
return -1;
}
/* Block if the TX FIFO is full */
while (u->FRbits.TXFF);
u->DR = data;
return 1;
}
void uart_poweron(uart_t uart)
{
}
void uart_poweroff(uart_t uart)
{
}
#endif /* UART_NUMOF */

View File

@ -7,7 +7,7 @@
*/
/**
* @ingroup cpu_sam3x8e
* @ingroup cpu_cc2538
* @{
*
* @file reboot_arch.c

View File

@ -7,19 +7,34 @@
*/
/**
* @ingroup cpu_sam3x8e
* @ingroup cpu_cc2538
* @{
*
* @file startup.c
* @brief Startup code and interrupt vector definition
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
* @author Ian Martin <ian@locicontrols.com>
*/
#include <stdint.h>
#include "cc2538-gpio.h"
#include "board.h"
#include "periph_conf.h"
/**
* @brief Convert an interrupt number to an interrupt vector offset
*
* @param[in] inum Interrupt number as defined in the "IRQn" enum, may be negative.
*
* @return Corresponding nonnegative vector offset
*/
#define INUM_TO_IVEC(inum) ( (inum) + 16 )
void isr_uart0(void) __attribute__((weak, alias("dummy_handler")));
void isr_uart1(void) __attribute__((weak, alias("dummy_handler")));
void default_handler(void) __attribute__((weak, alias("dummy_handler")));
/**
* memory markers as defined in the linker script
@ -58,12 +73,12 @@ void reset_handler(void)
uint32_t *src = &_etext;
/* load data section from flash to ram */
for (dst = &_srelocate; dst < &_erelocate; ) {
for (dst = &_srelocate; dst < &_erelocate;) {
*(dst++) = *(src++);
}
/* default bss section to zero */
for (dst = &_szero; dst < &_ezero; ) {
for (dst = &_szero; dst < &_ezero;) {
*(dst++) = 0;
}
@ -78,156 +93,160 @@ void reset_handler(void)
/**
* @brief Default handler is called in case no interrupt handler was defined
*/
__attribute__((naked))
void dummy_handler(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
__attribute__((naked))
void isr_nmi(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
__attribute__((naked))
void isr_mem_manage(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
__attribute__((naked))
void isr_debug_mon(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
__attribute__((naked))
void isr_hard_fault(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
__attribute__((naked))
void isr_bus_fault(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
__attribute__((naked))
void isr_usage_fault(void)
{
while (1) {asm ("nop");}
while (1) {
asm("nop");
}
}
/* Cortex-M specific interrupt vectors */
void isr_svc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_pendsv(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_systick(void) __attribute__ ((weak, alias("dummy_handler")));
/* SAM3X8E specific interrupt vector */
void isr_supc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_rstc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_rtc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_rtt(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_wdt(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_pmc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_efc0(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_efc1(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_uart(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_smc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_pioa(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_piob(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_pioc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_piod(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_usart0(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_usart1(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_usart2(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_usart3(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_hsmci(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_twi0(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_twi1(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_spi0(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_ssc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc0(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc1(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc2(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc3(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc4(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc5(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc6(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc7(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_tc8(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_pwm(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_adc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_dacc(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_dmac(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_uotghs(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_trng(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_emac(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_can0(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_can1(void) __attribute__ ((weak, alias("dummy_handler")));
void isr_svc(void) __attribute__((weak, alias("dummy_handler")));
void isr_pendsv(void) __attribute__((weak, alias("dummy_handler")));
void isr_systick(void) __attribute__((weak, alias("dummy_handler")));
/* interrupt vector table */
__attribute__ ((section(".vectors")))
__attribute__((section(".vectors")))
const void *interrupt_vector[] = {
/* Stack pointer */
(void*) (&_estack), /* pointer to the top of the empty stack */
[0] = &_estack, /* pointer to the top of the empty stack */
/* Cortex-M handlers */
(void*) reset_handler, /* entry point of the program */
(void*) isr_nmi, /* non maskable interrupt handler */
(void*) isr_hard_fault, /* if you end up here its not good */
(void*) isr_mem_manage, /* memory controller interrupt */
(void*) isr_bus_fault, /* also not good to end up here */
(void*) isr_usage_fault, /* autsch */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) isr_svc, /* system call interrupt */
(void*) isr_debug_mon, /* debug interrupt */
(void*) (0UL), /* Reserved */
(void*) isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */
(void*) isr_systick, /* SysTick interrupt, not used in RIOT */
/* STM specific peripheral handlers */
(void*) isr_supc, /* 0 supply controller */
(void*) isr_rstc, /* 1 reset controller */
(void*) isr_rtc, /* 2 real time clock */
(void*) isr_rtt, /* 3 real timer timer */
(void*) isr_wdt, /* 4 watchdog timer */
(void*) isr_pmc, /* 5 power management controller */
(void*) isr_efc0, /* 6 enhanced flash controller 0 */
(void*) isr_efc1, /* 7 enhanced flash controller 1 */
(void*) isr_uart, /* 8 universal asynchronous receiver transceiver */
(void*) isr_smc, /* 9 static memory controller */
(void*) (0UL),
(void*) isr_pioa, /* 11 GPIO port A */
(void*) isr_piob, /* 12 GPIO port B */
(void*) isr_pioc, /* 13 GPIO port C */
(void*) isr_piod, /* 14 GPIO port D */
(void*) (0UL),
(void*) (0UL),
(void*) isr_usart0, /* 17 USART0 */
(void*) isr_usart1, /* 18 USART1 */
(void*) isr_usart2, /* 19 USART2 */
(void*) isr_usart3, /* 20 USART3 */
(void*) isr_hsmci, /* 21 multimedia card interface */
(void*) isr_twi0, /* 22 two-wire interface 0 */
(void*) isr_twi1, /* 23 two-wire interface 1 */
(void*) isr_spi0, /* 24 serial peripheral interface */
(void*) (0UL),
(void*) isr_ssc, /* 26 synchronous serial controller */
(void*) isr_tc0, /* 27 timer counter 0 */
(void*) isr_tc1, /* 28 timer counter 1 */
(void*) isr_tc2, /* 29 timer counter 2 */
(void*) isr_tc3, /* 30 timer counter 3 */
(void*) isr_tc4, /* 31 timer counter 4 */
(void*) isr_tc5, /* 32 timer counter 5 */
(void*) isr_tc6, /* 33 timer counter 6 */
(void*) isr_tc7, /* 34 timer counter 7 */
(void*) isr_tc8, /* 35 timer counter 8 */
(void*) isr_pwm, /* 36 pulse width modulation controller */
(void*) isr_adc, /* 37 ADC controller */
(void*) isr_dacc, /* 38 DAC controller */
(void*) isr_dmac, /* 39 DMA controller */
(void*) isr_uotghs, /* 40 USB OTG high speed */
(void*) isr_trng, /* 41 true random number generator */
(void*) isr_emac, /* 42 Ethernet MAC*/
(void*) isr_can0, /* 43 CAN controller 0*/
(void*) isr_can1, /* 44 CAN controller 1*/
[INUM_TO_IVEC(ResetHandler_IRQn)] = reset_handler, /* entry point of the program */
[INUM_TO_IVEC(NonMaskableInt_IRQn)] = isr_nmi, /* non maskable interrupt handler */
[INUM_TO_IVEC(HardFault_IRQn)] = isr_hard_fault, /* if you end up here its not good */
[INUM_TO_IVEC(MemoryManagement_IRQn)] = isr_mem_manage, /* memory controller interrupt */
[INUM_TO_IVEC(BusFault_IRQn)] = isr_bus_fault, /* also not good to end up here */
[INUM_TO_IVEC(UsageFault_IRQn)] = isr_usage_fault, /* autsch */
[INUM_TO_IVEC(SVCall_IRQn)] = isr_svc, /* system call interrupt */
[INUM_TO_IVEC(DebugMonitor_IRQn)] = isr_debug_mon, /* debug interrupt */
[INUM_TO_IVEC(PendSV_IRQn)] = isr_pendsv, /* pendSV interrupt, used for task switching in RIOT */
[INUM_TO_IVEC(SysTick_IRQn)] = isr_systick, /* SysTick interrupt, not used in RIOT */
/* CC2538 specific peripheral handlers */
[INUM_TO_IVEC(GPIO_PORT_A_IRQn)] = gpio_port_a_isr, /**< GPIO port A */
[INUM_TO_IVEC(GPIO_PORT_B_IRQn)] = gpio_port_b_isr, /**< GPIO port B */
[INUM_TO_IVEC(GPIO_PORT_C_IRQn)] = gpio_port_c_isr, /**< GPIO port C */
[INUM_TO_IVEC(GPIO_PORT_D_IRQn)] = gpio_port_d_isr, /**< GPIO port D */
[INUM_TO_IVEC(UART_0_IRQ)] = isr_uart0, /**< RIOT UART 0 */
[INUM_TO_IVEC(UART_1_IRQ)] = isr_uart1, /**< RIOT UART 1 */
[INUM_TO_IVEC(SSI0_IRQn)] = default_handler, /**< SSI0 */
[INUM_TO_IVEC(I2C_IRQn)] = default_handler, /**< I2C */
[INUM_TO_IVEC(ADC_IRQn)] = default_handler, /**< ADC */
[INUM_TO_IVEC(WDT_IRQn)] = default_handler, /**< Watchdog Timer */
#if TIMER_0_EN
[INUM_TO_IVEC(TIMER_0_IRQn_1)] = isr_timer0_chan0, /**< RIOT Timer 0 Channel 0 */
[INUM_TO_IVEC(TIMER_0_IRQn_2)] = isr_timer0_chan1, /**< RIOT Timer 0 Channel 1 */
#endif
#if TIMER_1_EN
[INUM_TO_IVEC(TIMER_1_IRQn_1)] = isr_timer1_chan0, /**< RIOT Timer 1 Channel 0 */
[INUM_TO_IVEC(TIMER_1_IRQn_2)] = isr_timer1_chan1, /**< RIOT Timer 1 Channel 1 */
#endif
#if TIMER_2_EN
[INUM_TO_IVEC(TIMER_2_IRQn_1)] = isr_timer2_chan0, /**< RIOT Timer 2 Channel 0 */
[INUM_TO_IVEC(TIMER_2_IRQn_2)] = isr_timer2_chan1, /**< RIOT Timer 2 Channel 1 */
#endif
#if TIMER_3_EN
[INUM_TO_IVEC(TIMER_3_IRQn_1)] = isr_timer3_chan0, /**< RIOT Timer 3 Channel 0 */
[INUM_TO_IVEC(TIMER_3_IRQn_2)] = isr_timer3_chan1, /**< RIOT Timer 3 Channel 1 */
#endif
[INUM_TO_IVEC(ADC_CMP_IRQn)] = default_handler, /**< Analog Comparator */
[INUM_TO_IVEC(RF_RXTX_ALT_IRQn)] = default_handler, /**< RF TX/RX (Alternate) */
[INUM_TO_IVEC(RF_ERR_ALT_IRQn)] = default_handler, /**< RF Error (Alternate) */
[INUM_TO_IVEC(SYS_CTRL_IRQn)] = default_handler, /**< System Control */
[INUM_TO_IVEC(FLASH_CTRL_IRQn)] = default_handler, /**< Flash memory control */
[INUM_TO_IVEC(AES_ALT_IRQn)] = default_handler, /**< AES (Alternate) */
[INUM_TO_IVEC(PKA_ALT_IRQn)] = default_handler, /**< PKA (Alternate) */
[INUM_TO_IVEC(SM_TIMER_ALT_IRQn)] = default_handler, /**< SM Timer (Alternate) */
[INUM_TO_IVEC(MAC_TIMER_ALT_IRQn)] = default_handler, /**< MAC Timer (Alternate) */
[INUM_TO_IVEC(SSI1_IRQn)] = default_handler, /**< SSI1 */
[INUM_TO_IVEC(UDMA_IRQn)] = default_handler, /**< uDMA software */
[INUM_TO_IVEC(UDMA_ERR_IRQn)] = default_handler, /**< uDMA error */
[INUM_TO_IVEC(USB_IRQn)] = default_handler, /**< USB */
[INUM_TO_IVEC(RF_RXTX_IRQn)] = default_handler, /**< RF Core Rx/Tx */
[INUM_TO_IVEC(RF_ERR_IRQn)] = default_handler, /**< RF Core Error */
[INUM_TO_IVEC(AES_IRQn)] = default_handler, /**< AES */
[INUM_TO_IVEC(PKA_IRQn)] = default_handler, /**< PKA */
[INUM_TO_IVEC(SM_TIMER_IRQn)] = default_handler, /**< SM Timer */
[INUM_TO_IVEC(MACTIMER_IRQn)] = default_handler, /**< MAC Timer */
};
#if UPDATE_CCA
/**
* @brief Flash Customer Configuration Area (CCA)
*
* Defines bootloader backdoor configuration, boot image validity and base address, and flash page lock bits.
*/
__attribute__((section(".flashcca"), used))
const uint32_t cca[] = {
/* Bootloader Backdoor Configuration: */
0xe0ffffff | (CCA_BACKDOOR_ENABLE << 28) | (CCA_BACKDOOR_ACTIVE_LEVEL << 27) | (CCA_BACKDOOR_PORT_A_PIN << 24),
0x00000000, /**< Image Valid */
(uintptr_t)interrupt_vector, /**< Application Entry Point */
/* Unlock all pages and debug: */
0xffffffff,
0xffffffff,
0xffffffff,
0xffffffff,
0xffffffff,
0xffffffff,
0xffffffff,
0xffffffff,
};
#endif
/** @} */

View File

@ -7,11 +7,11 @@
*/
/**
* @ingroup cpu_sam3x8e
* @ingroup cpu_cc2538
* @{
*
* @file syscalls.c
* @brief NewLib system calls implementations for SAM3X8E
* @brief NewLib system calls implementations for CC2538
*
* @author Michael Baar <michael.baar@fu-berlin.de>
* @author Stefan Pfeiffer <pfeiffer@inf.fu-berlin.de>
@ -31,22 +31,58 @@
#include "board.h"
#include "thread.h"
#include "kernel.h"
#include "mutex.h"
#include "ringbuffer.h"
#include "irq.h"
#include "periph/uart.h"
#ifdef MODULE_UART0
#include "board_uart0.h"
#endif
/**
* manage the heap
*/
extern uint32_t _end; /* address of last used memory cell */
caddr_t heap_top = (caddr_t)&_end + 4;
caddr_t heap_top = (caddr_t) &_end + 4;
#ifndef MODULE_UART0
/**
* @brief use mutex for waiting on incoming UART chars
*/
static mutex_t uart_rx_mutex;
static char rx_buf_mem[STDIO_RX_BUFSIZE];
static ringbuffer_t rx_buf;
#endif
/**
* @brief Receive a new character from the UART and put it into the receive buffer
*/
void rx_cb(void *arg, char data)
{
#ifndef MODULE_UART0
(void)arg;
ringbuffer_add_one(&rx_buf, data);
mutex_unlock(&uart_rx_mutex);
#else
if (uart0_handler_pid) {
uart0_handle_incoming(data);
uart0_notify_thread();
}
#endif
}
/**
* @brief Initialize NewLib, called by __libc_init_array() from the startup script
*/
void _init(void)
{
uart_init_blocking(STDIO, STDIO_BAUDRATE);
#ifndef MODULE_UART0
mutex_init(&uart_rx_mutex);
ringbuffer_init(&rx_buf, rx_buf_mem, STDIO_RX_BUFSIZE);
#endif
uart_init(STDIO, STDIO_BAUDRATE, rx_cb, 0, 0);
}
/**
@ -69,7 +105,8 @@ void _exit(int n)
{
printf("#! exit %i: resetting\n", n);
NVIC_SystemReset();
while(1);
while (1);
}
/**
@ -84,7 +121,7 @@ void _exit(int n)
*
* @return [description]
*/
caddr_t _sbrk_r(struct _reent *r, ptrdiff_t incr)
caddr_t _sbrk_r(struct _reent *r, size_t incr)
{
unsigned int state = disableIRQ();
caddr_t res = heap_top;
@ -152,11 +189,16 @@ int _open_r(struct _reent *r, const char *name, int mode)
*/
int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count)
{
char c;
char *buff = (char*)buffer;
uart_read_blocking(UART_0, &c);
buff[0] = c;
#ifndef MODULE_UART0
while (rx_buf.avail == 0) {
mutex_lock(&uart_rx_mutex);
}
return ringbuffer_get(&rx_buf, (char*)buffer, rx_buf.avail);
#else
char *res = (char*)buffer;
res[0] = (char)uart0_readc();
return 1;
#endif
}
/**
@ -176,10 +218,12 @@ int _read_r(struct _reent *r, int fd, void *buffer, unsigned int count)
*/
int _write_r(struct _reent *r, int fd, const void *data, unsigned int count)
{
char *c = (char*)data;
char *c = (char *)data;
for (int i = 0; i < count; i++) {
uart_write_blocking(UART_0, c[i]);
uart_write_blocking(STDIO, c[i]);
}
return count;
}
@ -222,7 +266,7 @@ _off_t _lseek_r(struct _reent *r, int fd, _off_t pos, int dir)
*
* @return TODO
*/
int _fstat_r(struct _reent *r, int fd, struct stat * st)
int _fstat_r(struct _reent *r, int fd, struct stat *st)
{
r->_errno = ENODEV; /* not implemented yet */
return -1;
@ -254,7 +298,8 @@ int _stat_r(struct _reent *r, char *name, struct stat *st)
int _isatty_r(struct _reent *r, int fd)
{
r->_errno = 0;
if(fd == STDOUT_FILENO || fd == STDERR_FILENO) {
if (fd == STDOUT_FILENO || fd == STDERR_FILENO) {
return 1;
}
else {
@ -270,7 +315,7 @@ int _isatty_r(struct _reent *r, int fd)
*
* @return TODO
*/
int _unlink_r(struct _reent *r, char* path)
int _unlink_r(struct _reent *r, char *path)
{
r->_errno = ENODEV; /* not implemented yet */
return -1;

View File

@ -31,7 +31,7 @@ QUIET ?= 1
BOARD_BLACKLIST := arduino-due avsextrem chronos mbed_lpc1768 msb-430h msba2 redbee-econotag \
telosb wsn430-v1_3b wsn430-v1_4 msb-430 pttu udoo qemu-i386 z1 stm32f0discovery \
stm32f3discovery stm32f4discovery pca10000 pca10005 iot-lab_M3 arduino-mega2560 \
msbiot yunjia-nrf51822 samr21-xpro
msbiot yunjia-nrf51822 samr21-xpro cc2538dk
# This example only works with native for now.
# msb430-based boards: msp430-g++ is not provided in mspgcc.
@ -47,6 +47,7 @@ BOARD_BLACKLIST := arduino-due avsextrem chronos mbed_lpc1768 msb-430h msba2 red
# arduino-mega2560: cstdio header missing from avr-libc
# msbiot g++ does not support some used flags (e.g. -mthumb...)
# samr21-xpro g++ does not support some used flags (e.g. -mthumb...)
# cc2538dk: g++ does not support some used flags (e.g. -mthumb...)
# others: untested.
# If you want to add some extra flags when compile c++ files, add these flags