diff --git a/boards/cc2650stk/Makefile b/boards/cc2650stk/Makefile new file mode 100644 index 0000000000..f8fcbb53a0 --- /dev/null +++ b/boards/cc2650stk/Makefile @@ -0,0 +1,3 @@ +MODULE = board + +include $(RIOTBASE)/Makefile.base diff --git a/boards/cc2650stk/Makefile.features b/boards/cc2650stk/Makefile.features new file mode 100644 index 0000000000..8f81826a8b --- /dev/null +++ b/boards/cc2650stk/Makefile.features @@ -0,0 +1,11 @@ +# Put defined MCU peripherals here (in alphabetical order) +FEATURES_PROVIDED += periph_cpuid +FEATURES_PROVIDED += periph_gpio +FEATURES_PROVIDED += periph_timer +FEATURES_PROVIDED += periph_uart + +# Various other features (if any) +FEATURES_PROVIDED += cpp + +# The board MPU family (used for grouping by the CI system) +FEATURES_MCU_GROUP = cortex_m3_1 diff --git a/boards/cc2650stk/Makefile.include b/boards/cc2650stk/Makefile.include new file mode 100644 index 0000000000..f6cca7a734 --- /dev/null +++ b/boards/cc2650stk/Makefile.include @@ -0,0 +1,14 @@ +export CPU = cc26x0 +export CPU_MODEL = cc26x0f128 + +# set default port depending on operating system +PORT_LINUX ?= /dev/ttyACM0 +PORT_DARWIN ?= $(firstword $(sort $(wildcard /dev/tty.SLAB_USBtoUART*))) + +# setup serial terminal +include $(RIOTBOARD)/Makefile.include.serial + +# configure the flash tool +export UNIFLASH_PATH ?= "UNIFLASH_PATH unconfigured" +export FLASHER = $(UNIFLASH_PATH)/uniflash.sh +export FFLAGS = -ccxml $(RIOTBOARD)/$(BOARD)/dist/cc26x0stk.ccxml -program $(ELFFILE) diff --git a/boards/cc2650stk/board.c b/boards/cc2650stk/board.c new file mode 100644 index 0000000000..fcbeb8d96e --- /dev/null +++ b/boards/cc2650stk/board.c @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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 boards_cc2650stk + * @{ + * + * @file + * @brief Board specific implementations for the CC2650STK board + * + * @author Leon M. George + * + * @} + */ + +#include "cpu.h" +#include "board.h" + +/** + * @brief initialise the board + */ +void board_init(void) +{ + cpu_init(); + + gpio_init(LED0_PIN, GPIO_OUT); + gpio_init(LED1_PIN, GPIO_OUT); +} diff --git a/boards/cc2650stk/dist/cc26x0stk.ccxml b/boards/cc2650stk/dist/cc26x0stk.ccxml new file mode 100644 index 0000000000..210180b8b2 --- /dev/null +++ b/boards/cc2650stk/dist/cc26x0stk.ccxml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/boards/cc2650stk/include/board.h b/boards/cc2650stk/include/board.h new file mode 100644 index 0000000000..558cc7b254 --- /dev/null +++ b/boards/cc2650stk/include/board.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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 boards_cc2650stk CC2650STK + * @ingroup boards + * @brief SimpleLinkā„¢ CC2650 sensor tag + * @{ + * + * @file + * @brief Board configuration for the CC2650STK + * + * @author Leon M. George + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#include "periph/gpio.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Xtimer configuration + * @{ + */ +#define XTIMER_MASK (0xFFFF0000) +#define XTIMER_SHIFT_ON_COMPARE (7) +/** @} */ + +/** + * @brief On-board button configuration + * @{ + */ +#define BUTTON1_DIO GPIO_PIN(0, 4) +#define BUTTON2_DIO GPIO_PIN(0, 0) +/** @} */ + +/** + * @brief Macros for controlling the on-board LEDs + * @{ + */ +#define LED0_PIN GPIO_PIN(0, 10) +#define LED1_PIN GPIO_PIN(0, 15) + +#define LED0_ON gpio_set(LED0_PIN) +#define LED0_OFF gpio_clear(LED0_PIN) +#define LED0_TOGGLE gpio_toggle(LED0_PIN) + +#define LED1_ON gpio_set(LED1_PIN) +#define LED1_OFF gpio_clear(LED1_PIN) +#define LED1_TOGGLE gpio_toggle(LED1_PIN) +/** @} */ + +/** + * @brief Initialize board specific hardware, including clock, LEDs, and std-IO + */ +void board_init(void); + +#ifdef __cplusplus +} +#endif + +#endif /* BOARD_H_ */ +/** @} */ diff --git a/boards/cc2650stk/include/periph_conf.h b/boards/cc2650stk/include/periph_conf.h new file mode 100644 index 0000000000..89a18186e5 --- /dev/null +++ b/boards/cc2650stk/include/periph_conf.h @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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 boards_cc2650stk + * @{ + * + * @file + * @brief Peripheral MCU configuration for the CC2650STK board + * + * @author Leon M. George + */ + +#ifndef PERIPH_CONF_H_ +#define PERIPH_CONF_H_ + +#include "periph_cpu.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Clock configuration + * @{ + */ +/* the main clock is fixed to 48MHZ */ +#define CLOCK_CORECLOCK (48000000U) +/** @} */ + +/** + * @brief Timer configuration + * @{ + */ +static const timer_conf_t timer_config[] = { + { + .dev = GPT0, + .num = 0 + }, + { + .dev = GPT1, + .num = 1 + } +}; + +#define TIMER_0_ISR isr_timer0_chan0 +#define TIMER_1_ISR isr_timer1_chan0 + +#define TIMER_NUMOF (sizeof(timer_config) / sizeof(timer_config[0])) +/** @} */ + +/** + * @brief UART configuration + * + * The used CC26x0 CPU only supports a single UART device, so all we need to + * configure are the RX and TX pins. + * + * Optionally we can enable hardware flow control, by setting UART_HW_FLOW_CTRL + * to 1 and defining pins for UART_CTS_PIN and UART_RTS_PIN. + * @{ + */ +#define UART_NUMOF (1) +#define UART_RX_PIN (28) +#define UART_TX_PIN (29) +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CONF_H_ */ +/** @} */ diff --git a/cpu/cc26x0/Makefile b/cpu/cc26x0/Makefile new file mode 100644 index 0000000000..67506e130a --- /dev/null +++ b/cpu/cc26x0/Makefile @@ -0,0 +1,7 @@ +# Define the module that is built: +MODULE = cpu + +# Add a list of subdirectories, that should also be built: +DIRS = periph $(RIOTCPU)/cortexm_common + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/cc26x0/Makefile.include b/cpu/cc26x0/Makefile.include new file mode 100644 index 0000000000..507f47d21b --- /dev/null +++ b/cpu/cc26x0/Makefile.include @@ -0,0 +1,3 @@ +export CPU_ARCH := cortex-m3 + +include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/cc26x0/cpu.c b/cpu/cc26x0/cpu.c new file mode 100644 index 0000000000..2f4f55ecd2 --- /dev/null +++ b/cpu/cc26x0/cpu.c @@ -0,0 +1,54 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief implementation of the CPU initialization + * + * @author Leon M. George + * @} + */ + + #include "cpu.h" + #include "periph_conf.h" + +#ifndef HF_CLOCK_SOURCE +#define HF_CLOCK_SOURCE DDI_0_OSC_CTL0_SCLK_HF_SRC_SEL_RCOSC /* set 48MHz RCOSC */ +#endif +#ifndef LF_CLOCK_SOURCE +#define LF_CLOCK_SOURCE DDI_0_OSC_CTL0_SCLK_LF_SRC_SEL_HF_RCOSC /* set 31.25kHz derived from 48MHz RCOSC */ +#endif + +/** + *@brief Configure the MCU system clock + */ +static void cpu_clock_init(void); + +/** + * @brief Initialize the CPU, set IRQ priorities + */ +void cpu_init(void) +{ + /* initialize the Cortex-M core */ + cortexm_init(); + + /* initialize the system clock */ + cpu_clock_init(); +} + +static void cpu_clock_init(void) +{ + AON_WUC->AUXCTL |= AUXCTL_AUX_FORCE_ON; /* power on AUX_PD */ + while(!(AON_WUC->PWRSTAT & PWRSTAT_AUX_PD_ON)); /* wait for AUX_PD to be powered on */ + AUX_WUC->MODCLKEN0 |= MODCLKEN0_AUX_DDI0_OSC_EN; /* turn on oscillator interface clock */ + + DDI_0_OSC->CTL0 |= HF_CLOCK_SOURCE | LF_CLOCK_SOURCE; /* configure HF and LF clocks */ +} diff --git a/cpu/cc26x0/doc.txt b/cpu/cc26x0/doc.txt new file mode 100644 index 0000000000..57f6fb4326 --- /dev/null +++ b/cpu/cc26x0/doc.txt @@ -0,0 +1,15 @@ +/** + * @defgroup cpu_cc26x0 Texas Instruments CC26x0 + * @ingroup cpu + * @brief Texas Instruments CC26x0 Cortex-M3 MCU specific code + */ + +/** + * @defgroup cpu_specific_peripheral_memory_map + * @ingroup cpu + */ + +/** + * @defgroup cpu_cc26x0_definitions Texas Instruments CC26x0 definitions + * @ingroup cpu_cc26x0 + */ diff --git a/cpu/cc26x0/include/cc26x0.h b/cpu/cc26x0/include/cc26x0.h new file mode 100644 index 0000000000..3ddbac92fa --- /dev/null +++ b/cpu/cc26x0/include/cc26x0.h @@ -0,0 +1,117 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 MCU interrupt definitions + * + * @author Leon M. George + */ + +#ifndef CC26x0_H +#define CC26x0_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +typedef volatile uint8_t reg8_t; +typedef volatile uint32_t reg32_t; + +/** @addtogroup CC26x0_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 */ + + /****** CC26x0 specific Interrupt Numbers *********************************/ + EDGE_DETECT_IRQN = 0, /**< 16 AON edge detect */ + I2C_IRQN = 1, /**< 17 I2C */ + RF_CPE1_IRQN = 2, /**< 18 RF Command and Packet Engine 1 */ + SPIS_IRQN = 3, /**< 19 AON SpiSplave Rx, Tx and CS */ + AON_RTC_IRQN = 4, /**< 20 AON RTC */ + UART0_IRQN = 5, /**< 21 UART0 Rx and Tx */ + AON_AUX_SWEV0_IRQN = 6, /**< 22 Sensor Controller software event 0, through AON domain*/ + SSI0_IRQN = 7, /**< 23 SSI0 Rx and Tx */ + SSI1_IRQN = 8, /**< 24 SSI1 Rx and Tx */ + RF_CPE0_IRQN = 9, /**< 25 RF Command and Packet Engine 0 */ + RF_HW_IRQN = 10, /**< 26 RF Core Hardware */ + RF_CMD_ACK_IRQN = 11, /**< 27 RF Core Command Acknowledge */ + I2S_IRQN = 12, /**< 28 I2S */ + AON_AUX_SWEV1_IRQN = 13, /**< 29 Sensor Controller software event 1, through AON domain*/ + WATCHDOG_IRQN = 14, /**< 30 Watchdog timer */ + GPTIMER_0A_IRQN = 15, /**< 31 Timer 0 subtimer A */ + GPTIMER_0B_IRQN = 16, /**< 32 Timer 0 subtimer B */ + GPTIMER_1A_IRQN = 17, /**< 33 Timer 1 subtimer A */ + GPTIMER_1B_IRQN = 18, /**< 34 Timer 1 subtimer B */ + GPTIMER_2A_IRQN = 19, /**< 35 Timer 2 subtimer A */ + GPTIMER_2B_IRQN = 20, /**< 36 Timer 2 subtimer B */ + GPTIMER_3A_IRQN = 21, /**< 37 Timer 3 subtimer A */ + GPTIMER_3B_IRQN = 22, /**< 38 Timer 3 subtimer B */ + CRYPTO_IRQN = 23, /**< 39 Crypto Core Result available */ + UDMA_IRQN = 24, /**< 40 uDMA Software */ + UDMA_ERR_IRQN = 25, /**< 41 uDMA Error */ + FLASH_CTRL_IRQN = 26, /**< 42 Flash controller */ + SW0_IRQN = 27, /**< 43 Software Event 0 */ + AUX_COMBO_IRQN = 28, /**< 44 AUX combined event, directly to MCU domain*/ + AON_PRG0_IRQN = 29, /**< 45 AON programmable 0 */ + PROG_IRQN = 30, /**< 46 Dynamic Programmable interrupt (default source: PRCM)*/ + AUX_COMPA_IRQN = 31, /**< 47 AUX Comparator A */ + AUX_ADC_IRQN = 32, /**< 48 AUX ADC IRQ */ + TRNG_IRQN = 33, /**< 49 TRNG event */ + + IRQN_COUNT = (TRNG_IRQN + 1) /**< Number of peripheral IDs */ +} IRQn_Type; + +/** + * @brief Configuration of the Cortex-M3 processor and core peripherals + */ + +#define __MPU_PRESENT 1 /**< CC26x0 does provide a MPU */ +#define __NVIC_PRIO_BITS 3 /**< CC26x0 offers priority levels from 0..7 */ +#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick config is used */ + +#define RCOSC48M_FREQ 48000000 /**< 48 MHz */ +#define RCOSC24M_FREQ 24000000 /**< 24 MHz */ + +/** + * @brief CMSIS includes + */ +#include +/*@}*/ + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define FLASH_BASE 0x00000000 /**< FLASH base address */ +/*@}*/ + +#ifdef __cplusplus +} +#endif + +#endif /* CC26x0_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_aux.h b/cpu/cc26x0/include/cc26x0_aux.h new file mode 100644 index 0000000000..a790bb63d4 --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_aux.h @@ -0,0 +1,258 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 AUX register definitions + */ + +#ifndef CC26x0_AUX_H +#define CC26x0_AUX_H + +#include + +#include "cc26x0.h" + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * AUX_AIODIO registers + */ +typedef struct { + reg32_t GPIODOUT; /**< gpio data out */ + reg32_t IOMODE; /**< input output mode */ + reg32_t GPIODIN; /**< gpio data in */ + reg32_t GPIODOUTSET; /**< gpio data out set */ + reg32_t GPIODOUTCLR; /**< gpio data out clear */ + reg32_t GPIODOUTTGL; /**< gpio data out toggle */ + reg32_t GPIODIE; /**< gpio data input enable */ +} aux_aiodio_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_AIODIO0_BASE 0x400C1000 /**< AUX_AIODIO0 base address */ +#define AUX_AIODIO1_BASE 0x400C2000 /**< AUX_AIODIO1 base address */ +/** @} */ + +#define AUX_AIODIO0 ((aux_aiodio_regs_t *) (AUX_AIODIO0_BASE)) /**< AUX_AIODIO0 register bank */ +#define AUX_AIODIO1 ((aux_aiodio_regs_t *) (AUX_AIODIO1_BASE)) /**< AUX_AIODIO1 register bank */ + + +/** + * AUX_TDC registers + */ +typedef struct { + reg32_t CTL; /**< control */ + reg32_t STAT; /**< status */ + reg32_t RESULT; /**< result */ + reg32_t SATCFG; /**< saturaion configuration */ + reg32_t TRIGSRC; /**< trigger source */ + reg32_t TRIGCNT; /**< trigger counter */ + reg32_t TRIGCNTLOAD; /**< trigger counter load */ + reg32_t TRIGCNTCFG; /**< trigger counter config */ + reg32_t PRECTL; /**< prescaler control */ + reg32_t PRECNT; /**< prescaler counter */ +} aux_tdc_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_TDC_BASE 0x400C4000 /**< AUX_TDC base address */ +/** @} */ + +#define AUX_TDC ((aux_tdc_regs_t *) (AUX_TDC_BASE)) /**< AUX_TDC register bank */ + + +/** + * AUX_EVCTL registers + */ +typedef struct { + reg32_t VECCFG0; /**< vector config 0 */ + reg32_t VECCFG1; /**< vector config 1 */ + reg32_t SCEWEVSEL; /**< sensor controller engine wait event selection */ + reg32_t EVTOAONFLAGS; /**< events to AON domain flags */ + reg32_t EVTOAONPOL; /**< events to AON domain polarity */ + reg32_t DMACTL; /**< direct memoty access control */ + reg32_t SWEVSET; /**< software event set */ + reg32_t EVSTAT0; /**< event status 0 */ + reg32_t EVSTAT1; /**< event status 1 */ + reg32_t EVTOMCUPOL; /**< event to MCU domain polarity */ + reg32_t EVTOMCUFLAGS; /**< event to MCU domain flags */ + reg32_t COMBEVTOMCUMASK; /**< combined event to MCU domain mask */ + reg32_t __reserved; /**< meh */ + reg32_t VECFLAGS; /**< vector flags */ + reg32_t EVTOMCUFLAGSCLR; /**< events to MCU domain flags clear */ + reg32_t EVTOAONFLAGSCLR; /**< events to AON domain clear */ + reg32_t VECFLAGSCLR; /**< vector flags clear */ +} aux_evtcl_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_EVCTL_BASE 0x400C5000 /**< AUX_EVCTL base address */ +/** @} */ + +#define AUX_EVCTL ((aux_evctl_regs_t *) (AUX_EVCTL_BASE)) /**< AUX_EVCTL register bank */ + + +/** + * AUX_WUC registers + */ +typedef struct { + reg32_t MODCLKEN0; /**< module clock enable */ + reg32_t PWROFFREQ; /**< power off request */ + reg32_t PWRDWNREQ; /**< power down request */ + reg32_t PWRDWNACK; /**< power down acknowledgement */ + reg32_t CLKLFREQ; /**< low frequency clock request */ + reg32_t CLKLFACK; /**< low frequency clock acknowledgement */ + reg32_t __reserved1[4]; /**< meh */ + reg32_t WUEVFLAGS; /**< wake-up event flags */ + reg32_t WUEVCLR; /**< wake-up event clear */ + reg32_t ADCCLKCTL; /**< ADC clock control */ + reg32_t TDCCLKCTL; /**< TDC clock control */ + reg32_t REFCLKCTL; /**< reference clock control */ + reg32_t RTCSUBSECINC0; /**< real time counter sub second increment 0 */ + reg32_t RTCSUBSECINC1; /**< real time counter sub second increment 1 */ + reg32_t RTCSUBSECINCCTL; /**< real time counter sub second increment control */ + reg32_t MCUBUSCTL; /**< MCU bus control */ + reg32_t MCUBUSSTAT; /**< MCU bus status */ + reg32_t AONCTLSTAT; /**< AON domain control status */ + reg32_t AUXIOLATCH; /**< AUX input output latch */ + reg32_t MODCLKEN1; /**< module clock enable 1 */ +} aux_wuc_regs_t; + +/** + * @brief AUX_WUC register values + * @{ + */ +#define MODCLKEN0_SMPH_EN 0x00000001 /* enable clock for AUX_SMPH */ +#define MODCLKEN0_AIODIO0_EN 0x00000002 /* enable clock for AUX_AIODIO0 */ +#define MODCLKEN0_AIODIO1_EN 0x00000004 /* enable clock for AUX_AIODIO1 */ +#define MODCLKEN0_TIMER_EN 0x00000008 /* enable clock for AUX_TIMER */ +#define MODCLKEN0_ANAIF_EN 0x00000010 /* enable clock for AUX_ANAIF */ +#define MODCLKEN0_TDC_EN 0x00000020 /* enable clock for AUX_TDC */ +#define MODCLKEN0_AUX_DDI0_OSC_EN 0x00000040 /* enable clock for AUX_DDI0_OSC */ +#define MODCLKEN0_AUX_ADI4_EN 0x00000080 /* enable clock for AUX_ADI4 */ +/** @} */ + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_WUC_BASE 0x400C6000 /**< AUX_WUC base address */ +/** @} */ + +#define AUX_WUC ((aux_wuc_regs_t *) (AUX_WUC_BASE)) /**< AUX_WUC register bank */ + + +/** + * AUX_TIMER registers + */ +typedef struct { + reg32_t T0CFG; /**< timer 0 config */ + reg32_t T1CFG; /**< timer 1 config */ + reg32_t T0CTL; /**< timer 0 control */ + reg32_t T0TARGET; /**< timer 0 target */ + reg32_t T1TARGET; /**< timer 1 target */ + reg32_t T1CTL; /**< timer 1 control */ +} aux_timer_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_TIMER_BASE 0x400C7000 /**< AUX_WUC base address */ +/** @} */ + +#define AUX_TIMER ((aux_timer_regs_t *) (AUX_TIMER_BASE)) /**< AUX_TIMER register bank */ + + +/** + * AUX_SMPH registers + */ +typedef struct { + reg32_t SMPH0; /**< semaphore 0 */ + reg32_t SMPH1; /**< semaphore 1 */ + reg32_t SMPH2; /**< semaphore 2 */ + reg32_t SMPH3; /**< semaphore 3 */ + reg32_t SMPH4; /**< semaphore 4 */ + reg32_t SMPH5; /**< semaphore 5 */ + reg32_t SMPH6; /**< semaphore 6 */ + reg32_t SMPH7; /**< semaphore 7 */ + reg32_t AUTOTAKE; /**< sticky request for single semaphore */ +} aux_smph_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_SMPH_BASE 0x400C8000 /**< AUX_WUC base address */ +/* @} */ + +#define AUX_SMPH ((aux_smph_regs_t *) (AUX_SMPH_BASE)) /**< AUX_SMPH register bank */ + + +/** + * AUX_ANAIF registers + */ +typedef struct { + reg32_t __reserved[4]; /**< meh */ + reg32_t ADCCTL; /**< ADC control */ + reg32_t ADCFIFOSTAT; /**< ADC fifo status */ + reg32_t ADCFIFO; /**< ADC fifo */ + reg32_t ADCTRIG; /**< ADC trigger */ + reg32_t ISRCCTL; /**< current source control */ +} aux_anaif_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AUX_ANAIF_BASE 0x400C9000 /**< AUX_WUC base address */ +/** @} */ + +#define AUX_ANAIF ((aux_anaif_regs_t *) (AUX_ANAIF_BASE)) /**< AUX_ANAIF register bank */ + + +/** + * ADI_4_AUX registers + */ +typedef struct { + reg8_t MUX0; /**< multiplexer 0 */ + reg8_t MUX1; /**< multiplexer 1 */ + reg8_t MUX2; /**< multiplexer 2 */ + reg8_t MUX3; /**< multiplexer 3 */ + reg8_t ISRC; /**< current source */ + reg8_t COMP; /**< comparator */ + reg8_t MUX4; /**< multiplexer 4 */ + reg8_t ADC0; /**< ADC control 0 */ + reg8_t ADC1; /**< ADC control 1 */ + reg8_t ADCREF0; /**< ADC reference 0 */ + reg8_t ADCREF1; /**< ADC reference 1 */ +} adi_4_aux_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define ADI_4_AUX_BASE 0x400CB000 /**< AUX_WUC base address */ +/** @} */ + +#define ADI_4_AUX ((adi_4_aux_regs_t *) (ADI_4_AUX_BASE)) /**< ADI_4_AUX register bank */ + + +#define ADDI_SEM AUX_SMPH->SMPH0 /**< the semamphore used for ADDI */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x0_AUX_H */ + +/** @}*/ diff --git a/cpu/cc26x0/include/cc26x0_ccfg.h b/cpu/cc26x0/include/cc26x0_ccfg.h new file mode 100644 index 0000000000..89d2ffc9ec --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_ccfg.h @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 CCFG register definitions + */ + +#ifndef CC26x0_CCFG_H +#define CC26x0_CCFG_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define CCFG_BASE 0x50003000 /**< base address of CCFG memory */ +/*@}*/ + +/* TODO not present in datasheet but explained in cc26x0ware-lds */ +#define CCFG_SIZE_AND_DIS_FLAGS_DIS_GPRAM 0x00000004 /**< CCFG_SIZE_AND_DIS_FLAGS_DIS_GPRAM */ + +/** + * CCFG registers + */ +typedef struct { + reg32_t EXT_LF_CLK; /**< extern LF clock config */ + reg32_t MODE_CONF_1; /**< mode config 1 */ + reg32_t SIZE_AND_DIS_FLAGS; /**< CCFG size and disable flags */ + reg32_t MODE_CONF; /**< mmode config 0 */ + reg32_t VOLT_LOAD_0; /**< voltage load 0 */ + reg32_t VOLT_LOAD_1; /**< voltage load 1 */ + reg32_t RTC_OFFSET; /**< RTC offset */ + reg32_t FREQ_OFFSET; /**< frequency offset */ + reg32_t IEEE_MAC_0; /**< IEEE MAC address 0 */ + reg32_t IEEE_MAC_1; /**< IEEE MAC address 1 */ + reg32_t IEEE_BLE_0; /**< IEEE BLE address 0 */ + reg32_t IEEE_BLE_1; /**< IEEE BLE address 1 */ + reg32_t BL_CONFIG; /**< bootloader config */ + reg32_t ERASE_CONF; /**< erase config */ + reg32_t CCFG_TI_OPTIONS; /**< TI options */ + reg32_t CCFG_TAP_DAP_0; /**< test access points enable 0 */ + reg32_t CCFG_TAP_DAP_1; /**< test access points enable 1 */ + reg32_t IMAGE_VALID_CONF; /**< image valid */ + reg32_t CCFG_PROT_31_0; /**< protect sectors 0-31 */ + reg32_t CCFG_PROT_63_32; /**< protect sectors 32-63 */ + reg32_t CCFG_PROT_95_64; /**< protect sectors 64-95 */ + reg32_t CCFG_PROT_127_96; /**< protect sectors 96-127 */ +} ccfg_regs_t; + +#define CCFG ((ccfg_regs_t *) (CCFG_BASE + 0xFA8)) /**< CCFG register bank */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x0_CCFG_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_fcfg.h b/cpu/cc26x0/include/cc26x0_fcfg.h new file mode 100644 index 0000000000..9450f79105 --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_fcfg.h @@ -0,0 +1,139 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 FCFG register definitions + */ + +#ifndef CC26x0_FCFG_H +#define CC26x0_FCFG_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define FCFG_BASE 0x50001000 /**< base address of FCFG memory */ +/*@}*/ + +/** + * FCFG registers + */ +typedef struct { + uint8_t __reserved1[0xA0]; /**< meh */ + /* TODO does it pad here? */ + reg32_t MISC_CONF_1; /**< misc config */ + reg32_t __reserved2[8]; /**< meh */ + reg32_t CONFIG_RF_FRONTEND_DIV5; /**< config of RF frontend in divide-by-5 mode */ + reg32_t CONFIG_RF_FRONTEND_DIV6; /**< config of RF frontend in divide-by-6 mode */ + reg32_t CONFIG_RF_FRONTEND_DIV10; /**< config of RF frontend in divide-by-10 mode */ + reg32_t CONFIG_RF_FRONTEND_DIV12; /**< config of RF frontend in divide-by-12 mode */ + reg32_t CONFIG_RF_FRONTEND_DIV15; /**< config of RF frontend in divide-by-15 mode */ + reg32_t CONFIG_RF_FRONTEND_DIV30; /**< config of RF frontend in divide-by-30 mode */ + reg32_t CONFIG_SYNTH_DIV5; /**< config of synthesizer in divide-by-5-mode */ + reg32_t CONFIG_SYNTH_DIV6; /**< config of synthesizer in divide-by-5-mode */ + reg32_t CONFIG_SYNTH_DIV10; /**< config of synthesizer in divide-by-10-mode */ + reg32_t CONFIG_SYNTH_DIV12; /**< config of synthesizer in divide-by-12-mode */ + reg32_t CONFIG_SYNTH_DIV15; /**< config of synthesizer in divide-by-15-mode */ + reg32_t CONFIG_SYNTH_DIV30; /**< config of synthesizer in divide-by-30-mode */ + reg32_t CONFIG_MISC_ADC_DIV5; /**< config of IFADC in divide-by-5-mode */ + reg32_t CONFIG_MISC_ADC_DIV6; /**< config of IFADC in divide-by-6-mode */ + reg32_t CONFIG_MISC_ADC_DIV10; /**< config of IFADC in divide-by-10-mode */ + reg32_t CONFIG_MISC_ADC_DIV12; /**< config of IFADC in divide-by-12-mode */ + reg32_t CONFIG_MISC_ADC_DIV15; /**< config of IFADC in divide-by-15-mode */ + reg32_t CONFIG_MISC_ADC_DIV30; /**< config of IFADC in divide-by-30-mode */ + reg32_t __reserved3[3]; /**< meh */ + reg32_t SHDW_DIE_ID_0; /**< shadow of JTAG_TAP::EFUSE::DIE_ID_0.* */ + reg32_t SHDW_DIE_ID_1; /**< shadow of JTAG_TAP::EFUSE::DIE_ID_1.* */ + reg32_t SHDW_DIE_ID_2; /**< shadow of JTAG_TAP::EFUSE::DIE_ID_2.* */ + reg32_t SHDW_DIE_ID_3; /**< shadow of JTAG_TAP::EFUSE::DIE_ID_3.* */ + reg32_t __reserved4[4]; /**< meh */ + reg32_t SHDW_OSC_BIAS_LDO_TRIM; /**< shadow of JTAG_TAP::EFUSE::BIAS_LDO_TIM.* */ + reg32_t SHDW_ANA_TRIM; /**< shadow of JTAG_TAP::EFUSE::ANA_TIM.* */ + reg32_t __reserved5[9]; /**< meh */ + reg32_t FLASH_NUMBER; /**< number of manufactoring lot that produced this unit */ + reg32_t FLASH_COORDINATE; /**< X and Y coordinates of this unit on the wafer */ + reg32_t FLASH_E_P; /**< flash erase and program setup time */ + reg32_t FLASH_C_E_P_R; /**< flash compaction, execute, program, and read */ + reg32_t FLASH_P_R_PV; /**< flash program, read, and program verify */ + reg32_t FLASH_EH_SEQ; /**< flash erase hold and sequence */ + reg32_t FLASH_VHV_E; /**< flash VHV erase */ + reg32_t FLASH_PP; /**< flash program pulse */ + reg32_t FLASH_PROG_EP; /**< flash program and erase pulse */ + reg32_t FLASH_ERA_PW; /**< flash erase pulse width */ + reg32_t FLASH_VHV; /**< flash VHV */ + reg32_t FLASH_VHV_PV; /**< flash VHV program verify */ + reg32_t FLASH_V; /**< flash voltages */ + reg32_t __reserved6[0x3E]; /**< meh */ + reg32_t USER_ID; /**< user identification */ + reg32_t __reserved7[6]; /**< meh */ + reg32_t FLASH_OTP_DATA3; /**< flash OTP data 3 */ + reg32_t ANA2_TRIM; /**< misc analog trim */ + reg32_t LDO_TRIM; /**< LDO trim */ + reg32_t __reserved8[0xB]; /**< meh */ + reg32_t MAC_BLE_0; /**< MAC BLE address 0 */ + reg32_t MAC_BLE_1; /**< MAC BLE address 1 */ + reg32_t MAC_15_4_0; /**< MAC IEEE 820.15.4 address 0 */ + reg32_t MAC_15_4_1; /**< MAC IEEE 820.15.4 address 1 */ + reg32_t __reserved9[4]; /**< meh */ + reg32_t FLASH_OTP_DATA4; /**< flash OTP data 4 */ + reg32_t MISC_TRIM; /**< misc trim parameters */ + reg32_t RCOSC_HF_TEMPCOMP; /**< RFOSC HF temperature compensation */ + reg32_t __reserved10; /**< meh */ + reg32_t ICEPICK_DEVICE_ID; /**< IcePick device identification */ + reg32_t FCFG1_REVISION; /**< FCFG1 revision */ + reg32_t MISC_OTP_DATA; /**< misc OTP data */ + reg32_t __reserved11[8]; /**< meh */ + reg32_t IOCONF; /**< IO config */ + reg32_t __reserved12; /**< meh */ + reg32_t CONFIG_IF_ADC; /**< config of IF_ADC */ + reg32_t CONFIG_OSC_TOP; /**< config of OSC */ + reg32_t CONFIG_RF_FRONTEND; /**< config of RF frontend in dividy-by-2-mode */ + reg32_t CONFIG_SYNTH; /**< config of synthesizer in dividy-by-2-mode */ + reg32_t SOC_ADC_ABS_GAIN; /**< AUX_ADC gain in absolute reference mode */ + reg32_t SOC_ADC_REL_GAIN; /**< AUX_ADC gain in relative reference mode */ + reg32_t __reserved13; /**< meh */ + reg32_t SOC_ADC_OFFSET_INT; /**< AUX_ADC temperature offsets in absolute reference mode */ + reg32_t SOC_ADC_REF_TRIM_AND_OFFSET_EXT; /**< AUX_ADC reference trim and offset of external reference mode */ + reg32_t AMPCOMP_TH1; /**< amplitude compensation threshold 1 */ + reg32_t AMPCOMP_TH2; /**< amplitude compensation threshold 2 */ + reg32_t AMPCOMP_CTRL1; /**< amplitude compensation control */ + reg32_t ANABYPASS_VALUE2; /**< analog bypass value for OSC */ + reg32_t CONFIG_MISC_ADC; /**< config of IFADC in divide-by-2-mode */ + reg32_t __reserved14; /**< meh */ + reg32_t VOLT_TRIM; /**< voltage trim */ + reg32_t OSC_CONF; /**< OSC configuration */ + reg32_t __reserved15; /**< meh */ + reg32_t CAP_TRIM; /**< capacitor trim (it says 'capasitor' in the manual - if you know what that is ;-) */ + reg32_t MISC_OTP_DATA_1; /**< misc OSC control */ + reg32_t PWD_CURR_20C; /**< power down current control 20C */ + reg32_t PWD_CURR_35C; /**< power down current control 35C */ + reg32_t PWD_CURR_50C; /**< power down current control 50C */ + reg32_t PWD_CURR_65C; /**< power down current control 65C */ + reg32_t PWD_CURR_80C; /**< power down current control 80C */ + reg32_t PWD_CURR_95C; /**< power down current control 95C */ + reg32_t PWD_CURR_110C; /**< power down current control 110C */ + reg32_t PWD_CURR_125C; /**< power down current control 125C */ +} fcfg_regs_t; + +#define FCFG ((fcfg_regs_t *) (FCFG_BASE)) /**< FCFG register bank */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x0_FCFG_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_gpio.h b/cpu/cc26x0/include/cc26x0_gpio.h new file mode 100644 index 0000000000..7e4c81a59e --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_gpio.h @@ -0,0 +1,63 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief Driver for the cc26x0 GPIO controller + * + * @author Leon George + * + */ + +#ifndef CC26x0_GPIO_H +#define CC26x0_GPIO_H + +#include "cc26x0.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define GPIO_BASE (0x40022000) /**< GPIO base address */ +/** @} */ + +/** + * GPIO registers + */ +typedef struct { + reg32_t DOUT_FRAG[8]; /**< w the first bit of each byte corresponds to one bit of DOUT */ + reg32_t __reserved1[24]; /**< unused */ + reg32_t DOUT; /**< r/w state of the output */ + reg32_t __reserved2[3]; /**< unused */ + reg32_t DOUTSET; /**< w1s set output */ + reg32_t __reserved3[3]; /**< unused */ + reg32_t DOUTCLR; /**< w1c clear output */ + reg32_t __reserved4[3]; /**< unused */ + reg32_t DOUTTGL; /**< r/w toggle output */ + reg32_t __reserved5[3]; /**< unused */ + reg32_t DIN; /**< r input status */ + reg32_t __reserved6[3]; /**< unused */ + reg32_t DOE; /**< r/w enable output */ + reg32_t __reserved7[3]; /**< unused */ + reg32_t EVFLAGS; /**< r/w1c indicates an input event */ +} gpio_regs_t; + +#define GPIO ((gpio_regs_t *) (GPIO_BASE)) /**< GPIO register bank */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x0_GPIO_H */ + +/** @} */ diff --git a/cpu/cc26x0/include/cc26x0_gpt.h b/cpu/cc26x0/include/cc26x0_gpt.h new file mode 100644 index 0000000000..a6ce5b5043 --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_gpt.h @@ -0,0 +1,211 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief definitions for the CC26x0 GPT moduls + * + * @author Leon George + */ + +#ifndef CC26x0_GPT_H +#define CC26x0_GPT_H + +#include "cc26x0.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief GPT registers + */ +typedef struct { + reg32_t CFG; /**< config */ + reg32_t TAMR; /**< timer A mode */ + reg32_t TBMR; /**< timer B mode */ + reg32_t CTL; /**< control */ + reg32_t SYNC; /**< sync timers */ + reg32_t __reserved1; /**< unused */ + reg32_t IMR; /**< interrupt mask register */ + reg32_t RIS; /**< raw interrupt status */ + reg32_t MIS; /**< masked interrupt status */ + reg32_t ICLR; /**< interrupt clear */ + reg32_t TAILR; /**< timer A interval load register */ + reg32_t TBILR; /**< timer B interval load register */ + reg32_t TAMATCHR; /**< timer A match register */ + reg32_t TBMATCHR; /**< timer B match register */ + reg32_t TAPR; /**< timer A pre-scale */ + reg32_t TBPR; /**< timer B pre-scale */ + reg32_t TAPMR; /**< timer A pre-scale match register */ + reg32_t TBPMR; /**< timer B pre-scale match register */ + reg32_t TAR; /**< timer A register */ + reg32_t TBR; /**< timer B register */ + reg32_t TAV; /**< timer A value */ + reg32_t TBV; /**< timer B value */ + reg32_t RTCPD; /**< config */ + reg32_t TAPS; /**< config */ + reg32_t TBPS; /**< config */ + reg32_t TAPV; /**< config */ + reg32_t TBPV; /**< config */ + reg32_t DMAEV; /**< config */ + reg32_t __reserved2[976]; /**< config */ + reg32_t VERSION; /**< config */ + reg32_t ANDCCP; /**< config */ +} gpt_reg_t; + +/** + * @brief GPT base register addresses + * @{ + */ +#define GPT0_BASE (0x40010000) /**< GTP0 base address */ +#define GPT1_BASE (0x40011000) /**< GTP1 base address */ +#define GPT2_BASE (0x40012000) /**< GTP2 base address */ +#define GPT3_BASE (0x40013000) /**< GTP3 base address */ +/** @} */ + +/** + * @brief GPT instances + * @{ + */ +#define GPT0 ((gpt_reg_t *) (GPT0_BASE)) +#define GPT1 ((gpt_reg_t *) (GPT1_BASE)) +#define GPT2 ((gpt_reg_t *) (GPT2_BASE)) +#define GPT3 ((gpt_reg_t *) (GPT3_BASE)) +/** @} */ + +/** + * @brief GPT register values + * @{ + */ +#define GPT_CFG_32T 0 +#define GPT_CFG_32RTC 1 +#define GPT_CFG_16T 4 + +#define GPT_TXMR_TXMR_ONE_SHOT 0x00000001 +#define GPT_TXMR_TXMR_PERIODIC 0x00000002 +#define GPT_TXMR_TXMR_CAPTURE 0x00000003 +#define GPT_TXMR_TXCM_EDGECNT 0x00000000 +#define GPT_TXMR_TXCM_EDGETIME 0x00000004 +#define GPT_TXMR_TXAMS_CAPTCOMP 0x00000000 +#define GPT_TXMR_TXAMS_PWM 0x00000008 +#define GPT_TXMR_TXCDIR_DOWN 0x00000000 +#define GPT_TXMR_TXCDIR_UP 0x00000010 /* starts from 0 */ +#define GPT_TXMR_TXMIE 0x00000020 /* match interrupt */ +#define GPT_TXMR_TXWOT 0x00000040 /* wait on trigger from daisy */ +#define GPT_TXMR_TXSNAPS 0x00000080 +#define GPT_TXMR_TXILD_CLOCK 0x00000000 /* interrupt loac: update TXPR or TXR */ +#define GPT_TXMR_TXILD_TIMEOUT 0x00000100 +#define GPT_TXMR_TXPWMIE 0x00000200 +#define GPT_TXMR_TXMRSU 0x00000400 +#define GPT_TXMR_TXPLO 0x00000800 +#define GPT_TXMR_TXCIN 0x00001000 +#define GPT_TXMR_TCACT_DIS 0x00000000 +#define GPT_TXMR_TCACT_TGL_TO 0x00002000 +#define GPT_TXMR_TCACT_CLR_TO 0x00004000 +#define GPT_TXMR_TCACT_SET_TO 0x00006000 +#define GPT_TXMR_TCACT_SET_NOW_TGL_TO 0x00008000 +#define GPT_TXMR_TCACT_CLR_NOW_TGL_TO 0x0000a000 +#define GPT_TXMR_TCACT_SET_NOW_CLR_TO 0x0000c000 +#define GPT_TXMR_TCACT_CLR_NOW_SET_TO 0x0000e000 + +#define GPT_CTL_TAEN 0x00000001 +#define GPT_CTL_TASTALL 0x00000002 +#define GPT_CTL_TAEVENT_POS 0x00000000 +#define GPT_CTL_TAEVENT_NEG 0x00000004 +#define GPT_CTL_TAEVENT_BOTH 0x0000000c +#define GPT_CTL_RTCEN 0x00000010 +#define GPT_CTL_TAPWML_INV 0x00000040 +#define GPT_CTL_TBEN 0x00000100 /* still need capture CFG */ +#define GPT_CTL_TBSTALL 0x00000200 +#define GPT_CTL_TBEVENT_POS 0x00000000 +#define GPT_CTL_TBEVENT_NEG 0x00000400 +#define GPT_CTL_TBEVENT_BOTH 0x00000c00 +#define GPT_CTL_TBPWML_INV 0x00004000 + +#define GPT_SYNC_SYNC1_A 0x00000001 +#define GPT_SYNC_SYNC1_B 0x00000002 +#define GPT_SYNC_SYNC2_A 0x00000004 +#define GPT_SYNC_SYNC2_B 0x00000008 +#define GPT_SYNC_SYNC3_A 0x00000010 +#define GPT_SYNC_SYNC3_B 0x00000020 +#define GPT_SYNC_SYNC4_A 0x00000040 +#define GPT_SYNC_SYNC4_B 0x00000080 + +#define GPT_IMR_TATOIM 0x00000001 +#define GPT_IMR_CAMIM 0x00000002 +#define GPT_IMR_CAEIM 0x00000004 +#define GPT_IMR_RTCIM 0x00000008 +#define GPT_IMR_TAMIM 0x00000010 +#define GPT_IMR_DMAAIM 0x00000020 +#define GPT_IMR_TBTOIM 0x00000100 +#define GPT_IMR_CBMIM 0x00000200 +#define GPT_IMR_CBEIM 0x00000400 +#define GPT_IMR_TBMIM 0x00000800 +#define GPT_IMR_DMABIM 0x00002000 +#define GPT_IMR_WUMIS 0x00010000 + +#define GPT_RIS_TATORIS 0x00000001 +#define GPT_RIS_CAMRIS 0x00000002 +#define GPT_RIS_CAERIS 0x00000004 +#define GPT_RIS_RTCRIS 0x00000008 +#define GPT_RIS_TAMRIS 0x00000010 +#define GPT_RIS_TBTORIS 0x00000100 +#define GPT_RIS_CBMRIS 0x00000200 +#define GPT_RIS_CBERIS 0x00000400 +#define GPT_RIS_TBMRIS 0x00000800 +#define GPT_RIS_DMARIS 0x00002000 +#define GPT_RIS_WURIS 0x00010000 + +#define GPT_MIS_TATOMIS 0x00000001 +#define GPT_MIS_CAMMIS 0x00000002 +#define GPT_MIS_CAEMIS 0x00000004 +#define GPT_MIS_RTCMIS 0x00000008 +#define GPT_MIS_TAMMIS 0x00000010 +#define GPT_MIS_TBTOMIS 0x00000100 +#define GPT_MIS_CBMMIS 0x00000200 +#define GPT_MIS_CBEMIS 0x00000400 +#define GPT_MIS_TBMMIS 0x00000800 +#define GPT_MIS_DMAMIS 0x00002000 +#define GPT_MIS_WUMIS 0x00010000 + +#define GPT_ICLR_TATOCINT 0x00000001 +#define GPT_ICLR_CAMCINT 0x00000002 +#define GPT_ICLR_CAECINT 0x00000004 +#define GPT_ICLR_RTCCINT 0x00000008 +#define GPT_ICLR_TAMCINT 0x00000010 +#define GPT_ICLR_TBTOCINT 0x00000100 +#define GPT_ICLR_CBMCINT 0x00000200 +#define GPT_ICLR_CBECINT 0x00000400 +#define GPT_ICLR_TBMCINT 0x00000800 +#define GPT_ICLR_DMACINT 0x00002000 +#define GPT_ICLR_WUCINT 0x00010000 + +#define GPT_DMAEV_TATODMAEN 0x00000001 +#define GPT_DMAEV_CAMDMAEN 0x00000002 +#define GPT_DMAEV_CAEDMAEN 0x00000004 +#define GPT_DMAEV_RTCDMAEN 0x00000008 +#define GPT_DMAEV_TAMDMAEN 0x00000010 +#define GPT_DMAEV_TBTODMAEN 0x00000100 +#define GPT_DMAEV_CBMDMAEN 0x00000200 +#define GPT_DMAEV_CBEDMAEN 0x00000400 +#define GPT_DMAEV_TBMDMAEN 0x00000800 +/** @} */ + +#define GPT_NUMOF 4 /**< GPT count */ +#define NUM_CHANNELS_PER_GPT 1 /**< GPT channel count */ + +#ifdef __cplusplus +} +#endif + +#endif /* CC26x0_GPT_H */ +/** @} */ diff --git a/cpu/cc26x0/include/cc26x0_i2c.h b/cpu/cc26x0/include/cc26x0_i2c.h new file mode 100644 index 0000000000..6a34c13b44 --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_i2c.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_i2c_definitions + * @{ + * + * @file + * @brief CC26x0 MCU I/O register definitions + * + * @author Leon George + */ + +#ifndef CC26x0_I2C_H +#define CC26x0_I2C_H + +#include "cc26x0.h" + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * I2C registers + */ +typedef struct { + reg32_t SOAR; /**< slave own address */ + union { + reg32_t SSTAT; /**< slave status */ + reg32_t SCTL; /**< slave control */ + }; + reg32_t SDR; /**< slave data */ + reg32_t SIMR; /**< slave interrupt mask */ + reg32_t SRIS; /**< slave raw interrupt status */ + reg32_t SMIS; /**< slave masked interrupt status */ + reg32_t SICR; /**< slave interrupt clear */ + reg32_t __reserved[0x1F9]; /**< meh */ + reg32_t MSA; /**< master slave address */ + union { + reg32_t MSTAT; /**< master status */ + reg32_t MCTRL; /**< master control */ + }; + reg32_t MDR; /**< master data */ + reg32_t MTPR; /**< master timer period */ + reg32_t MIMR; /**< master interrupt mask */ + reg32_t MRIS; /**< master raw interrupt status */ + reg32_t MMIS; /**< master masked interrupt statues */ + reg32_t MICR; /**< master interrupt clear */ + reg32_t MCR; /**< master configuration */ +} i2c_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define I2C_BASE (PERIPH_BASE + 0x2000) /**< I2C base address */ +/** @} */ + +#define I2C ((i2c_regs_t *) (I2C_BASE)) /**< I2C register bank */ + +#ifdef __cplusplus +} +#endif + +#endif /* CC26x0_I2C_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_ioc.h b/cpu/cc26x0/include/cc26x0_ioc.h new file mode 100644 index 0000000000..facf2b66db --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_ioc.h @@ -0,0 +1,164 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_ioc_definitions + * @{ + * + * @file + * @brief CC26x0 MCU I/O register definitions + * + * @author Leon George + */ + +#ifndef CC26x0_IOC_H +#define CC26x0_IOC_H + +#include "cc26x0.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define MCU_IOC_BASE (0x40081000) /**< IOC (MCU) base address */ +/** @} */ + + +/** + * @brief obtain IOCFG-register for a DIO + * + * @param[in] dio_num DIO number (0-31) + */ +typedef struct { + reg32_t CFG[32]; /**< config */ +} cc26x0_ioc_regs_t; + +#define IOC ((cc26x0_ioc_regs_t *)(MCU_IOC_BASE)) /**< IOC register banks */ + +/** + * @name values for IOCFG + * @{ + */ +#define IOCFG_PORTID_GPIO 0x00000000 /**< GPIO */ +#define IOCFG_PORTID_AON_SCS 0x00000001 /**< AON SPI-S SCS */ +#define IOCFG_PORTID_AON_SCK 0x00000002 /**< AON SPI-S SCK */ +#define IOCFG_PORTID_AON_SDI 0x00000003 /**< AON SPI-S SDI */ +#define IOCFG_PORTID_AON_SDO 0x00000004 /**< AON SPI-S SDO */ +#define IOCFG_PORTID_AON_CLK32K 0x00000007 /**< AON external 32kHz clock */ +#define IOCFG_PORTID_AUX_IO 0x00000008 /**< AUX IO */ +#define IOCFG_PORTID_SSI0_RX 0x00000009 /**< SSI0 receive */ +#define IOCFG_PORTID_SSI0_TX 0x0000000A /**< SSI0 transmit */ +#define IOCFG_PORTID_SSI0_FSS 0x0000000B /**< SSI0 FSS */ +#define IOCFG_PORTID_SSI0_CLK 0x0000000C /**< SSI0 clock */ +#define IOCFG_PORTID_I2C_MSSDA 0x0000000D /**< I2C data */ +#define IOCFG_PORTID_I2C_MSSCL 0x0000000E /**< I2C clock */ +#define IOCFG_PORTID_UART0_RX 0x0000000F /**< UART0 receive */ +#define IOCFG_PORTID_UART0_TX 0x00000010 /**< UART0 transmit */ +#define IOCFG_PORTID_UART0_CTS 0x00000011 /**< UART0 clear to send */ +#define IOCFG_PORTID_UART0_RTS 0x00000012 /**< UART0 request to send */ +#define IOCFG_PORTID_PORT_EVT0 0x00000017 /**< PORT EVENT 0 */ +#define IOCFG_PORTID_PORT_EVT1 0x00000018 /**< PORT EVENT 1 */ +#define IOCFG_PORTID_PORT_EVT2 0x00000019 /**< PORT EVENT 2 */ +#define IOCFG_PORTID_PORT_EVT3 0x0000001A /**< PORT EVENT 3 */ +#define IOCFG_PORTID_PORT_EVT4 0x0000001B /**< PORT EVENT 4 */ +#define IOCFG_PORTID_PORT_EVT5 0x0000001C /**< PORT EVENT 5 */ +#define IOCFG_PORTID_PORT_EVT6 0x0000001D /**< PORT EVENT 6 */ +#define IOCFG_PORTID_PORT_EVT7 0x0000001E /**< PORT EVENT 7 */ +#define IOCFG_PORTID_SWV 0x00000020 /**< serial wire viewer */ +#define IOCFG_PORTID_SSI1_RX 0x00000021 /**< SSI1 receive */ +#define IOCFG_PORTID_SSI1_TX 0x00000022 /**< SSI1 transmit */ +#define IOCFG_PORTID_SSI1_FSS 0x00000023 /**< SSI1 FSS */ +#define IOCFG_PORTID_SSI1_CLK 0x00000024 /**< SSI1 clock */ +#define IOCFG_PORTID_I2S_AD0 0x00000025 /**< I2S data 0 */ +#define IOCFG_PORTID_I2S_AD1 0x00000026 /**< I2S data 1 */ +#define IOCFG_PORTID_I2S_WCLK 0x00000027 /**< I2S frame/word clock */ +#define IOCFG_PORTID_I2S_BCLK 0x00000028 /**< I2S bit clock */ +#define IOCFG_PORTID_I2S_MCLK 0x00000029 /**< I2S master clock 2 */ +#define IOCFG_PORTID_RFC_TRC 0x0000002E /**< RF core trace */ +#define IOCFG_PORTID_RFC_GPO0 0x0000002F /**< RC core data out 0 */ +#define IOCFG_PORTID_RFC_GPO1 0x00000030 /**< RC core data out 1 */ +#define IOCFG_PORTID_RFC_GPO2 0x00000031 /**< RC core data out 2 */ +#define IOCFG_PORTID_RFC_GPO3 0x00000032 /**< RC core data out 3 */ +#define IOCFG_PORTID_RFC_GPI0 0x00000033 /**< RC core data in 0 */ +#define IOCFG_PORTID_RFC_GPI1 0x00000034 /**< RC core data in 1 */ +#define IOCFG_PORTID_RFC_SMI_DL_OUT 0x00000035 /**< RF core SMI data link out */ +#define IOCFG_PORTID_RFC_SMI_DL_IN 0x00000036 /**< RF core SMI data link in */ +#define IOCFG_PORTID_RFC_SMI_CMD_OUT 0x00000037 /**< RF core SMI command link out */ +#define IOCFG_PORTID_RFC_SMI_CMD_IN 0x00000038 /**< RF core SMI command link in */ + +#define IOCFG_IOSTR_AUTO 0x00000000 /**< automatic drive strength (2/4/8 mA @ VVDS) */ +#define IOCFG_IOSTR_MAX 0x00000300 /**< maximum drive strength (2/4/8 mA @ 1.8V) */ +#define IOCFG_IOSTR_MED 0x00000200 /**< medium drive strength (2/4/8 mA @ 2.5V) */ +#define IOCFG_IOSTR_MIN 0x00000100 /**< minimum drive strength (2/4/8 mA @ 3.3V) */ + +#define IOCFG_IOCURR_2MA 0x00000000 /**< 2mA drive strength */ +#define IOCFG_IOCURR_4MA 0x00000400 /**< 4mA drive strength */ +#define IOCFG_IOCURR_8MA 0x00000800 /**< 4 or 8mA drive strength */ +#define IOCFG_IOCURR_16MA 0x00000C00 /**< Up to 16mA drive strength */ + +#define IOCFG_SLEW_RED 0x00001000 /**< reduced slew rate */ + +#define IOCFG_PULLCTL_OFF 0x00006000 /**< no IO pull */ +#define IOCFG_PULLCTL_UP 0x00004000 /**< pull up */ +#define IOCFG_PULLCTL_DOWN 0x00002000 /**< pull down */ + +#define IOCFG_EDGEDET_FALLING 0x00010000 /**< edge detection on falling edge */ +#define IOCFG_EDGEDET_RISING 0x00020000 /**< edge detection on rising edge */ +#define IOCFG_EDGEDET_BOTH 0x00030000 /**< edge detection on both edges */ +#define IOCFG_EDGEIRQ_ENABLE 0x00040000 /**< enable interrupt on edge detect */ + +/* n/a when port_id is AON or AUX */ +#define IOCFG_IOMODE_INV 0x01000000 /**< inverted I/O */ +#define IOCFG_IOMODE_OPEN_DRAIN 0x04000000 /**< open drain */ +#define IOCFG_IOMODE_OPEN_SRC 0x06000000 /**< open source */ + +/* both enable waking up when port_id is AON or AUX */ +#define IOCFG_WUCFG_LOW 0x10000000 +#define IOCFG_WUCFG_HIGH 0x18000000 + +/* ignored if port_id is AUX */ +#define IOCFG_INPUT_ENABLE 0x20000000 + +#define IOCFG_HYST_ENABLE 0x40000000 +/** @} */ + + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AON_IOC_BASE (PERIPH_BASE + 0x94000) /**< always-on-IOC base address */ +/** @} */ + +/** + * AON registers + */ +typedef struct { + reg32_t IOSTRMIN; /**< IO drive strength minimum */ + reg32_t IOSTRMED; /**< IO drive strength medium */ + reg32_t IOSTRMAX; /**< IO drive strength maximum */ + reg32_t IOCLATCH; /**< IO latch control */ + reg32_t CLK32KCTL; /**< SCLK_LF external output control */ +} aon_regs_t; + +#define AON ((aon_regs_t *) (AON_IOC_BASE)) /**< AON register bank */ + +#define IOCLATCH_EN 0x00000001 /**< IO controlled by GPIO or peripheral; kept in AON otherwise */ + +#define CLK32KCTL_OEN 0x00000001 /**< don't output SCLK_LF on DIOs with PORT_ID AON_CLK32K */ + + +#ifdef __cplusplus +} +#endif + +#endif /* CC26x0_IOC_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_prcm.h b/cpu/cc26x0/include/cc26x0_prcm.h new file mode 100644 index 0000000000..5310d1d9da --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_prcm.h @@ -0,0 +1,322 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 PRCM register definitions + */ + +#ifndef CC26x0_PRCM_H +#define CC26x0_PRCM_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * DDI_0_OSC registers + */ +typedef struct { + reg32_t CTL0; /**< control 0 */ + reg32_t CTL1; /**< control 1 */ + reg32_t RADCEXTCFG; /**< RADC external config */ + reg32_t AMPCOMPCTL; /**< amplitude compensation control */ + reg32_t AMPCOMPTH1; /**< amplitude compensation threshold 1 */ + reg32_t AMPCOMPTH2; /**< amplitude compensation threshold 2 */ + reg32_t ANABYPASSVAL1; /**< analog bypass values 1 */ + reg32_t ANABYPASSVAL2; /**< analog bypass values 2 */ + reg32_t ATESTCTL; /**< analog test control */ + reg32_t ADCDOUBLERNANOAMPCTL; /**< ADC doubler nanoamp control */ + reg32_t XOSCHFCTL; /**< XOSCHF control */ + reg32_t LFOSCCTL; /**< low frequency oscillator control */ + reg32_t RCOSCHFCTL; /**< RCOSCHF control */ + reg32_t STAT0; /**< status 0 */ + reg32_t STAT1; /**< status 1 */ + reg32_t STAT2; /**< status 2 */ +} ddi0_osc_regs_t; + +/** + * @brief DDI_0_OSC register values + * @{ + */ +#define DDI_0_OSC_CTL0_SCLK_HF_SRC_SEL_RCOSC 0x0 +#define DDI_0_OSC_CTL0_SCLK_HF_SRC_SEL_XOSC 0x1 +#define DDI_0_OSC_CTL0_SCLK_MF_SRC_SEL 0x2 +#define DDI_0_OSC_CTL0_SCLK_LF_SRC_SEL_mask 0x6 +#define DDI_0_OSC_CTL0_SCLK_LF_SRC_SEL_HF_RCOSC 0x0 +#define DDI_0_OSC_CTL0_SCLK_LF_SRC_SEL_HF_XOSC 0x4 +#define DDI_0_OSC_CTL0_SCLK_LF_SRC_SEL_LF_RCOSC 0x8 +#define DDI_0_OSC_CTL0_SCLK_LF_SRC_SEL_LF_XOSC 0xC +#define DDI_0_OSC_CTL0_ACLK_REF_SRC_SEL_RCOSC_mask 0x60 +#define DDI_0_OSC_CTL0_ACLK_REF_SRC_SEL_RCOSC_HF 0x00 /* 31.25kHz */ +#define DDI_0_OSC_CTL0_ACLK_REF_SRC_SEL_XOSC_HF 0x20 /* 31.25kHz */ +#define DDI_0_OSC_CTL0_ACLK_REF_SRC_SEL_RCOSC_LF 0x40 /* 32kHz */ +#define DDI_0_OSC_CTL0_ACLK_REF_SRC_SEL_XOSC_LF 0x60 /* 32.768kHz */ +#define DDI_0_OSC_CTL0_ACLK_TDC_SRC_SEL_RCOSC_mask 0x180 +#define DDI_0_OSC_CTL0_ACLK_TDC_SRC_SEL_RCOSC_HF 0x000 /* 48MHz */ +#define DDI_0_OSC_CTL0_ACLK_TDC_SRC_SEL_RCOSC_LF 0x080 /* 48MHz */ +#define DDI_0_OSC_CTL0_ACLK_TDC_SRC_SEL_XOSC_HF 0x100 /* 24MHz */ +#define DDI_0_OSC_CTL0_CLK_LOSS_EN 0x200 /* enable clock loss detection */ +#define DDI_0_OSC_CTL0_XOSC_LF_DIG_BYPASS 0x400 /* bypass XOSC_LF and use digital input clock from AON foor xosx_lf (precuations in datasheet) */ +#define DDI_0_OSC_CTL0_XOSC_HF_POWER_MODE 0x800 +#define DDI_0_OSC_CTL0_RCOSC_LF_TRIMMED 0x1000 +#define DDI_0_OSC_CTL0_ALLOW_SCLK_HF_SWITCHING 0x10000 +#define DDI_0_OSC_CTL0_FORCE_KICKSTART_EN 0x400000 +#define DDI_0_OSC_CTL0_DOUBLER_RESET_DURATION 0x2000000 +#define DDI_0_OSC_CTL0_DOUBLER_START_DURATION_mask 0x6000000 +#define DDI_0_OSC_CTL0_BYPASS_RCOSC_LF_CLK_QUAL 0x10000000 +#define DDI_0_OSC_CTL0_BYPASS_XOSC_LF_CLK_QUAL 0x20000000 +#define DDI_0_OSC_CTL0_XTAL_IS_24M 0x80000000 +/** @} */ + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define DDI0_OSC_BASE 0x400CA000 /**< DDI0_OSC base address */ +/*@}*/ + +#define DDI_0_OSC ((ddi0_osc_regs_t *) (DDI0_OSC_BASE)) /**< DDI_0_OSC register bank */ + + +/** + * AON_SYSCTL registers + */ +typedef struct { + reg32_t PWRCTL; /**< power management */ + reg32_t RESETCTL; /**< reset management */ + reg32_t SLEEPCTL; /**< sleep mode */ +} aon_sysctl_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AON_SYSCTL_BASE 0x40090000 /**< AON_SYSCTL base address */ +/*@}*/ + +#define AON_SYSCTL ((aon_sysctl_regs_t *) (AON_SYSCTL_BASE)) /**< AON_SYSCTL register bank */ + + +/** + * AON_WUC registers + */ +typedef struct { + reg32_t MCUCLK; /**< MCU clock management */ + reg32_t AUXCLK; /**< AUX clock management */ + reg32_t MCUCFG; /**< MCU config */ + reg32_t AUXCFG; /**< AUX config */ + reg32_t AUXCTL; /**< AUX control */ + reg32_t PWRSTAT; /**< power status */ + reg32_t __reserved1; /**< meh */ + reg32_t SHUTDOWN; /**< shutdown control */ + reg32_t CTL0; /**< control 0 */ + reg32_t CTL1; /**< control 1 */ + reg32_t __reserved2[2]; /**< meh */ + reg32_t RECHARGECFG; /**< recharge controller config */ + reg32_t RECHARGESTAT; /**< recharge controller status */ + reg32_t __reserved3; /**< meh */ + reg32_t OSCCFG; /**< oscillator config */ + reg32_t JTAGCFG; /**< JTAG config */ + reg32_t JTAGUSERCODE; /**< JTAG USERCODE */ +} aon_wuc_regs_t; + +/** + * @brief AON_WUC register values + * @{ + */ +#define MCUCLK_PWR_DWN_SRC 0x1 /* SCLK_LF in powerdown (no clock elsewise) */ +#define MCUCLK_PWR_DWN_SRC_mask 0x3 +#define MCUCLK_RCOSC_HF_CAL_DONE 0x4 /* set by MCU bootcode. RCOSC_HF is calibrated to 48 MHz, allowing FLASH to power up */ + +#define AUXCLK_SRC_HF 0x1 /* SCLK for AUX */ +#define AUXCLK_SRC_LF 0x4 +#define AUXCLK_SRC_mask 0x7 /* garuanteed to be glitchless */ +#define AUXCLK_SCLK_HF_DIV_pos 8 /* don't set while SCLK_HF active for AUX */ +#define AUXCLK_SCLK_HF_DIV_mask 0x700 /* divisor will be 2^(value+1) */ +#define AUXCLK_PWR_DWN_SRC_pos 11 /* SCLK_LF in powerdown when SCLK_HF is source (no clock elsewise?!) */ +#define AUXCLK_PWR_DWN_SRC_mask 0x1800 /* datasheet is confusing.. */ + +#define MCUCFG_SRAM_RET_OFF 0x0 /* no retention for any SRAM-bank */ +#define MCUCFG_SRAM_RET_B0 0x1 +#define MCUCFG_SRAM_RET_B01 0x3 +#define MCUCFG_SRAM_RET_B012 0x7 +#define MCUCFG_SRAM_RET_B0124 0xF /* retention for banks 0, 1, 2, and 3 */ +#define MCUCFG_SRAM_FIXED_WU_EN 0x100 +#define MCUCFG_SRAM_VIRT_OFF 0x200 + +#define AUXCFG_RAM_RET_EN 0x1 /* retention for AUX_RAM bank 0. is off when otherwise in retention mode */ + +#define AUXCTL_AUX_FORCE_ON 0x1 +#define AUXCTL_SWEV 0x2 +#define AUXCTL_SCE_RUN_EN 0x3 +#define AUXCTL_RESET_REQ 0x80000000 + +#define PWRSTAT_AUX_RESET_DONE 0x2 +#define PWRSTAT_AUX_BUS_CONNECTED 0x4 +#define PWRSTAT_MCU_PD_ON 0x10 +#define PWRSTAT_AUX_PD_ON 0x20 +#define PWRSTAT_JTAG_PD_ON 0x40 +#define PWRSTAT_AUX_PWR_DNW 0x200 + +#define SHUTDOWN_EN 0x1 /* register/cancel shutdown request */ + +#define AONWUC_CTL0_MCU_SRAM_ERASE 0x4 +#define AONWUC_CTL0_AUX_SRAM_ERASE 0x8 +#define AONWUC_CTL0_PWR_DWN_DIS 0x10 /* disable powerdown on request */ + +#define AONWUC_CTL1_MCU_WARM_RESET 0x1 /* last MCU reset was a warm reset */ +#define AONWUC_CTL1_MCU_RESET_SRC 0x2 /* JTAG was source of last reset (MCU SW elsewise) */ + +#define RECHARGECFG_PER_E_mask 0x00000007 /* number of 32KHz clocks between activation of recharge controller: */ +#define RECHARGECFG_PER_M_mask 0x000000F8 /* computed as follows: PERIOD = (PER_M*16+15) * 2^(PER_E) */ +#define RECHARGECFG_MAX_PER_E_mask 0x00000700 /* maximum period the recharge algorithm can take */ +#define RECHARGECFG_MAX_PER_M_mask 0x0000F800 /* computed as follows: MAXCYCLES = (MAX_PER_M*16+15) * 2^(MAX_PER_E) */ +#define RECHARGECFG_C1_mask 0x000F0000 /* i resign */ +#define RECHARGECFG_C2_mask 0x000F0000 +#define RECHARGECFG_ADAPTIVE_EN 0x80000000 + +#define RECHARGESTAT_MAX_USED_PER_mask 0x0FFFF +#define RECHARGESTAT_VDDR_SMPLS_mask 0xF0000 + +#define OSCCFG_PER_E_mask 0x07 /* number of 32KHz clocks between oscillator amplitude callibrations */ +#define OSCCFG_PER_M_mask 0xF8 /* computed as follows: PERIOD = (PER_M*16+15) * 2^(PER_E) */ + +#define JTAGCFG_JTAG_PD_FORCE_ON 0x10 +/** @} */ + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define AON_WUC_BASE 0x40091000 /**< AON_WUC base address */ +/*@}*/ + +#define AON_WUC ((aon_wuc_regs_t *) (AON_WUC_BASE)) /**< AON_WUC register bank */ + + +/** + * PRCM registers + */ +typedef struct { + reg32_t INFRCLKDIVR; /**< infrastructure clock division factor for run mode */ + reg32_t INFRCLKDIVS; /**< infrastructure clock division factor for sleep mode */ + reg32_t INFRCLKDIVDS; /**< infrastructure clock division factor for deep sleep mode */ + reg32_t VDCTL; /**< MCU voltage domain control */ + reg32_t __reserved1[6]; /**< meh */ + reg32_t CLKLOADCTL; /**< clock load control */ + reg32_t RFCCLKG; /**< RFC clock gate */ + reg32_t VIMSCLKG; /**< VIMS clock gate */ + reg32_t __reserved2[2]; /**< meh */ + reg32_t SECDMACLKGR; /**< TRNG, CRYPTO, and UDMA clock gate for run mode */ + reg32_t SECDMACLKGS; /**< TRNG, CRYPTO, and UDMA clock gate for sleep mode */ + reg32_t SECDMACLKGDS; /**< TRNG, CRYPTO, and UDMA clock gate for deep sleep mode */ + reg32_t GPIOCLKGR; /**< GPIO clock gate for run mode */ + reg32_t GPIOCLKGS; /**< GPIO clock gate for sleep mode */ + reg32_t GPIOCLKGDS; /**< GPIO clock gate for deep sleep mode */ + reg32_t GPTCLKGR; /**< GPT clock gate for run mode */ + reg32_t GPTCLKGS; /**< GPT clock gate for sleep mode */ + reg32_t GPTCLKGDS; /**< GPT clock gate for deep sleep mode */ + reg32_t I2CCLKGR; /**< I2C clock gate for run mode */ + reg32_t I2CCLKGS; /**< I2C clock gate for sleep mode */ + reg32_t I2CCLKGDS; /**< I2C clock gate for deep sleep mode */ + reg32_t UARTCLKGR; /**< UART clock gate for run mode */ + reg32_t UARTCLKGS; /**< UART clock gate for sleep mode */ + reg32_t UARTCLKGDS; /**< UART clock gate for deep sleep mode */ + reg32_t SSICLKGR; /**< SSI clock gate for run mode */ + reg32_t SSICLKGS; /**< SSI clock gate for sleep mode */ + reg32_t SSICLKGDS; /**< SSI clock gate for deep sleep mode */ + reg32_t I2SCLKGR; /**< I2S clock gate for run mode */ + reg32_t I2SCLKGS; /**< I2S clock gate for sleep mode */ + reg32_t I2SCLKGDS; /**< I2S clock gate for deep sleep mode */ + reg32_t __reserved3[10]; /**< meh */ + reg32_t CPUCLKDIV; /**< CPU clock division factor */ + reg32_t __reserved4[3]; /**< meh */ + reg32_t I2SBCLKSEL; /**< I2S clock select */ + reg32_t GPTCLKDIV; /**< GPT scalar */ + reg32_t I2SCLKCTL; /**< I2S clock control */ + reg32_t I2SMCLKDIV; /**< MCLK division ratio */ + reg32_t I2SBCLKDIV; /**< BCLK division ratio */ + reg32_t I2SWCLKDIV; /**< WCLK division ratio */ + reg32_t __reserved5[11]; /**< meh */ + reg32_t SWRESET; /**< SW initiated resets */ + reg32_t WARMRESET; /**< WARM reset control and status */ + reg32_t __reserved6[6]; /**< meh */ + reg32_t PDCTL0; /**< power domain control */ + reg32_t PDCTL0RFC; /**< RFC power domain control */ + reg32_t PDCTL0SERIAL; /**< SERIAL power domain control */ + reg32_t PDCTL0PERIPH; /**< PERIPH power domain control */ + reg32_t __reserved7; /**< meh */ + reg32_t PDSTAT0; /**< power domain status */ + reg32_t PDSTAT0RFC; /**< RFC power domain status */ + reg32_t PDSTAT0SERIAL; /**< SERIAL power domain status */ + reg32_t PDSTAT0PERIPH; /**< PERIPH power domain status */ + reg32_t __reserved8[11]; /**< meh */ + reg32_t PDCTL1; /**< power domain control */ + reg32_t __reserved9; /**< power domain control */ + reg32_t PDCTL1CPU; /**< CPU power domain control */ + reg32_t PDCTL1RFC; /**< RFC power domain control */ + reg32_t PDCTL1VIMS; /**< VIMS power domain control */ + reg32_t __reserved10; /**< meh */ + reg32_t PDSTAT1; /**< power domain status */ + reg32_t PDSTAT1BUS; /**< BUS power domain status */ + reg32_t PDSTAT1RFC; /**< RFC power domain status */ + reg32_t PDSTAT1CPU; /**< CPU power domain status */ + reg32_t PDSTAT1VIMS; /**< VIMS power domain status */ + reg32_t __reserved11[10]; /**< meh */ + reg32_t RFCMODESEL; /**< selected RFC mode */ + reg32_t __reserved12[20]; /**< meh */ + reg32_t RAMRETEN; /**< memory retention control */ + reg32_t __reserved13; /**< meh */ + reg32_t PDRETEN; /**< power domain retention (undocumented) */ + reg32_t __reserved14[8]; /**< meh */ + reg32_t RAMHWOPT; /**< undocumented */ +} prcm_regs_t; + +/** + * @brief PRCM register values + * @{ + */ +#define CLKLOADCTL_LOAD 0x1 +#define CLKLOADCTL_LOADDONE 0x2 + +#define PDCTL0_RFC_ON 0x1 +#define PDCTL0_SERIAL_ON 0x2 +#define PDCTL0_PERIPH_ON 0x4 + +#define PDSTAT0_RFC_ON 0x1 +#define PDSTAT0_SERIAL_ON 0x2 +#define PDSTAT0_PERIPH_ON 0x4 + +#define PDCTL1_CPU_ON 0x2 +#define PDCTL1_RFC_ON 0x4 +#define PDCTL1_VIMS_ON 0x8 + +#define PDSTAT1_CPU_ON 0x2 +#define PDSTAT1_RFC_ON 0x4 +#define PDSTAT1_VIMS_ON 0x8 +/** @} */ + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define PRCM_BASE 0x40082000 /**< PRCM base address */ +/*@}*/ + +#define PRCM ((prcm_regs_t *) (PRCM_BASE)) /**< PRCM register bank */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x0_PRCM_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_uart.h b/cpu/cc26x0/include/cc26x0_uart.h new file mode 100644 index 0000000000..d0ca4a7f18 --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_uart.h @@ -0,0 +1,133 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 UART interface + * + */ + +#ifndef CC26x0_UART_H +#define CC26x0_UART_H + +#include "cc26x0.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define UART_BASE (0x40001000) /**< UART base address */ + +/** + * @brief UART component registers + */ +typedef struct { + reg32_t DR; /**< data */ + union { + reg32_t RSR; /**< status */ + reg32_t ECR; /**< error clear */ + }; + reg32_t __reserved1[4]; /**< meh */ + reg32_t FR; /**< flag */ + reg32_t __reserved2[2]; /**< meh */ + reg32_t IBRD; /**< integer baud-rate divisor */ + reg32_t FBRD; /**< fractional baud-rate divisor */ + reg32_t LCRH; /**< line control */ + reg32_t CTL; /**< control */ + reg32_t IFLS; /**< interrupt fifo level select */ + reg32_t IMSC; /**< interrupt mask set/clear */ + reg32_t RIS; /**< raw interrupt status */ + reg32_t MIS; /**< masked interrupt status */ + reg32_t ICR; /**< interrupt clear */ + reg32_t DMACTL; /**< DMA control */ +} uart_regs_t; + +/** + * @brief UART register values + * @{ + */ +#define UART_DR_DATA_mask 0xFF +#define UART_DR_FE 0x100 +#define UART_DR_PE 0x200 +#define UART_DR_BE 0x400 +#define UART_DR_OE 0x800 + +#define UART_ECR_FE 0x1 +#define UART_ECR_PE 0x2 +#define UART_ECR_BE 0x4 +#define UART_ECR_OE 0x8 + +#define UART_FR_CTS 0x1 +#define UART_FR_BUSY 0x4 +#define UART_FR_RXFE 0x10 +#define UART_FR_TXFF 0x20 +#define UART_FR_RXFF 0x40 +#define UART_FR_TXFE 0x80 + +#define UART_LCRH_PEN 0x1 +#define UART_LCRH_EPS 0x2 +#define UART_LCRH_RXFE 0x4 +#define UART_LCRH_STP2 0x8 +#define UART_LCRH_FEN 0x10 +#define UART_LCRH_WLEN_mask 0x60 +#define UART_LCRH_WLEN_5 0x0 +#define UART_LCRH_WLEN_6 0x20 +#define UART_LCRH_WLEN_7 0x40 +#define UART_LCRH_WLEN_8 0x60 +#define UART_LCRH_SPS 0x80 + +#define UART_CTL_UARTEN 0x1 +#define UART_CTL_LBE 0x80 +#define UART_CTL_TXE 0x100 +#define UART_CTL_RXE 0x200 +#define UART_CTL_RTS 0x800 +#define UART_CTL_RTSEN 0x4000 +#define UART_CTL_CTSEN 0x8000 + +#define UART_MIS_CTSMMIS 0x1 +#define UART_MIS_RXMIS 0x10 +#define UART_MIS_TXMIS 0x20 +#define UART_MIS_RTMIS 0x40 +#define UART_MIS_FEMIS 0x80 +#define UART_MIS_PEMIS 0x100 +#define UART_MIS_BEMIS 0x200 +#define UART_MIS_OEMIS 0x400 + +#define UART_IMSC_CTSMIM 0x2 +#define UART_IMSC_RXIM 0x10 +#define UART_IMSC_TXIM 0x20 +#define UART_IMSC_RTIM 0x40 +#define UART_IMSC_FEIM 0x80 +#define UART_IMSC_PEIM 0x100 +#define UART_IMSC_BEIM 0x200 +#define UART_IMSC_OEIM 0x400 + +#define UART_IFLS_TXSEL_1_8 0x0 +#define UART_IFLS_TXSEL_2_8 0x1 +#define UART_IFLS_TXSEL_4_8 0x2 +#define UART_IFLS_TXSEL_6_8 0x3 +#define UART_IFLS_TXSEL_7_8 0x4 + +#define UART_IFLS_RXSEL_1_8 0x0 +#define UART_IFLS_RXSEL_2_8 0x8 +#define UART_IFLS_RXSEL_4_8 0x10 +#define UART_IFLS_RXSEL_6_8 0x18 +#define UART_IFLS_RXSEL_7_8 0x20 +/** @} */ + +#define UART ((uart_regs_t *) (UART_BASE)) /**< UART register bank */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x8_UART_H */ +/** @} */ diff --git a/cpu/cc26x0/include/cc26x0_vims.h b/cpu/cc26x0/include/cc26x0_vims.h new file mode 100644 index 0000000000..c65fd4545e --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_vims.h @@ -0,0 +1,237 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 VIMS register definitions + */ + +#ifndef CC26x0_VIMS_H +#define CC26x0_VIMS_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * FLASH registers + */ +typedef struct { + reg32_t __reserved1[7]; /**< meh */ + reg32_t STAT; /**< FMC and efuse status */ + reg32_t CTL; /**< config */ + reg32_t __reserved2; /**< meh */ + reg32_t SYSCODE_START; /**< syscode start address offset config */ + reg32_t FLASH_SIZE; /**< flash size config */ + reg32_t __reserved3[3]; /**< meh */ + reg32_t FWLOCK; /**< firmware lock */ + reg32_t FWFLAG; /**< firmware flags */ + reg32_t __reserved4[0x3EF]; /**< meh */ + reg32_t EFUSE; /**< efuse instruction */ + reg32_t EFUSEADDR; /**< efuse address */ + reg32_t DATAUPPER; /**< efuse data - upper */ + reg32_t DATALOWER; /**< efuse data - lower */ + reg32_t EFUSECFG; /**< OCP sysconf */ + reg32_t EFUSESTAT; /**< system status */ + reg32_t ACC; /**< arbitrary instruction cound */ + reg32_t BOUNDARY; /**< boundary test register to drive I/O */ + reg32_t EFUSEFLAG; /**< efuse key loaded flag */ + reg32_t EFUSEKEY; /**< efuse key */ + reg32_t EFUSERELEASE; /**< efuese release */ + reg32_t EFUSEPINS; /**< efuse pins */ + reg32_t EFUSECRA; /**< efuse column repair address */ + reg32_t EFUSEREAD; /**< efuse read */ + reg32_t EFUSEPROGRAM; /**< efuse program */ + reg32_t EFUSEERROR; /**< efuse error */ + reg32_t SINGLEBIT; /**< single-bit error status */ + reg32_t TWOBIT; /**< two-bit error status */ + reg32_t SELFTESTCYC; /**< self-test cycles */ + reg32_t SELFTESTSIGN; /**< self-test signature */ + reg32_t __reserved5[0x3ec]; /**< meh */ + reg32_t FRDCTL; /**< FMC read control */ + reg32_t FSPRD; /**< FMC read margin control */ + reg32_t FEDACCTL1; /**< FMC error correction control 1 */ + reg32_t __reserved6[4]; /**< meh */ + reg32_t FEDACSTAT; /**< FMC error status */ + reg32_t __reserved7[4]; /**< meh */ + reg32_t FBPROT; /**< FMC bank protection */ + reg32_t FBSE; /**< FMC sector enable */ + reg32_t FBBUSY; /**< FMC bank busy */ + reg32_t FBAC; /**< FMC bank access control */ + reg32_t FBFALLBACK; /**< FMC bank fallback power */ + reg32_t FBPRDY; /**< FMC bank/pump ready */ + reg32_t FPAC1; /**< FMC pump access control 1 */ + reg32_t FPAC2; /**< FMC pump access control 2 */ + reg32_t FMAC; /**< FMC module access control */ + reg32_t FMSTAT; /**< FMC module status */ + reg32_t __reserved8[3]; /**< meh */ + reg32_t FLOCK; /**< FMC flash lock */ + reg32_t __reserved9[6]; /**< meh */ + reg32_t FVREADCT; /**< FMC VREADCT trim */ + reg32_t FVHVCT1; /**< FMC VHVCT1 trim */ + reg32_t FVHVCT2; /**< FMC VHVCT2 trim */ + reg32_t FVHVCT3; /**< FMC VHVCT3 trim */ + reg32_t FVNVCT; /**< FMC VNVCT trim */ + reg32_t FVSLP; /**< FMC VSL_P trim */ + reg32_t FVWLCT; /**< FMC VWLCT trim */ + reg32_t FEFUSECTL; /**< FMC efuse control */ + reg32_t FEFUSESTAT; /**< FMC efuse status */ + reg32_t FEFUSEDATA; /**< FMC efuse data */ + reg32_t FSEQPMP; /**< FMC sequential pump information */ + reg32_t __reserved10[21]; /**< meh */ + reg32_t FBSTROBES; /**< FMC bank signal strobe */ + reg32_t FPSTROBES; /**< FMC pump signal strobe */ + reg32_t FBMODE; /**< FMC bank and pump mode */ + reg32_t FTCR; /**< FMC test command control */ + reg32_t FADDR; /**< FMC bank address */ + reg32_t __reserved11[2]; /**< meh */ + reg32_t FTCTL; /**< FMC test control */ + reg32_t FWPWRITE0; /**< FMC flash wide programming write data 0 */ + reg32_t FWPWRITE1; /**< FMC flash wide programming write data 1 */ + reg32_t FWPWRITE2; /**< FMC flash wide programming write data 2 */ + reg32_t FWPWRITE3; /**< FMC flash wide programming write data 3 */ + reg32_t FWPWRITE4; /**< FMC flash wide programming write data 4 */ + reg32_t FWPWRITE5; /**< FMC flash wide programming write data 5 */ + reg32_t FWPWRITE6; /**< FMC flash wide programming write data 6 */ + reg32_t FWPWRITE7; /**< FMC flash wide programming write data 7 */ + reg32_t FWPWRITE_ECC; /**< FMC flash wide programming ECC */ + reg32_t FSWSTAT; /**< FMC software interface status */ + reg32_t __reserved12[0x2E]; /**< meh */ + reg32_t FSM_GLBCTL; /**< FMC FSM global controll */ + reg32_t FSM_STATE; /**< FMC FSM state status */ + reg32_t FSM_STAT; /**< FMC FSM status */ + reg32_t FSM_CMD; /**< FMC FSM command */ + reg32_t FSM_PE_OSU; /**< FMC FSM program/erase operation setup */ + reg32_t FSM_VSTAT; /**< FMC FSM voltage status setup */ + reg32_t FSM_PE_VSU; /**< FMC FSM program/erase verify setup */ + reg32_t FSM_CMP_VSU; /**< FMC FSM compare verify setup */ + reg32_t FSM_EX_VAL; /**< FMC FSM EXECUTEZ to valid data */ + reg32_t FSM_RD_H; /**< FMC FSM read mode hold */ + reg32_t FSM_P_OH; /**< FMC FSM program hold */ + reg32_t FSM_ERA_OH; /**< FMC FSM erase operation hold */ + reg32_t FSM_SAV_PPUL; /**< FMC FSM saved program pulses */ + reg32_t FSM_PE_VH; /**< FMC FSM program/erase verify hold */ + reg32_t __reserved13[2]; /**< meh */ + reg32_t FSM_PRG_PW; /**< FMC FSM program pulse width */ + reg32_t FSM_ERA_PW; /**< FMC FSM erase pulse width */ + reg32_t __reserved14[3]; /**< meh */ + reg32_t FSM_SAV_ERA_PUL; /**< FMC FSM saved erased pulses */ + reg32_t FSM_TIMER; /**< FMC FSM timer */ + reg32_t FSM_MODE; /**< FMC FSM MODE */ + reg32_t FSM_PGM; /**< FMC FSM program bits */ + reg32_t FSM_ERA; /**< FMC FSM erase bits */ + reg32_t FSM_PRG_PUL; /**< FMC FSM maximum programming pulses */ + reg32_t FSM_ERA_PUL; /**< FMC FSM maximum erase pulses */ + reg32_t FSM_STEP_SIZE; /**< FMC FSM EC step size */ + reg32_t FSM_PUL_CNTR; /**< FMC FSM pulse counter */ + reg32_t FSM_EC_STEP_HEIGHT; /**< FMC FSM EC step height */ + reg32_t FSM_ST_MACHINE; /**< FMC FSM ST MACHINE */ + reg32_t FSM_FLES; /**< FMC FSM FLES memory control bits */ + reg32_t __reserved15; /**< meh */ + reg32_t FSM_WR_ENA; /**< FMC FSM register write enable */ + reg32_t FSM_ACC_PP; /**< FMC FSM accumulate program pulses */ + reg32_t FSM_ACC_EP; /**< FMC FSM accumulate erase pulses */ + reg32_t __reserved16[3]; /**< meh */ + reg32_t FSM_ADDR; /**< FMC FSM address */ + reg32_t FSM_SECTOR; /**< FMC sectors erased */ + reg32_t FMC_REV_ID; /**< FMC revision identification */ + reg32_t FSM_ERR_ADDR; /**< FSM error address */ + reg32_t FSM_PGM_MAXPUL; /**< FMC FSM maximum program pulse */ + reg32_t FSM_EXECUTE; /**< FMC FSM command execute */ + reg32_t __reserved17[2]; /**< meh */ + reg32_t FSM_SECTOR1; /**< FMC FSM sector erased 1 */ + reg32_t FSM_SECTOR2; /**< FMC FSM sector erased 2 */ + reg32_t __reserved18[6]; /**< meh */ + reg32_t FSM_BSLE0; /**< FMC FSM bank sector lock erase 0 */ + reg32_t FSM_BSLE1; /**< FMC FSM bank sector lock erase 1 */ + reg32_t __reserved19[2]; /**< meh */ + reg32_t FSM_BSLP0; /**< FMC FSM bank sector lock program 0 */ + reg32_t FSM_BSLP1; /**< FMC FSM bank sector lock program 1 */ + reg32_t __reserved20[0x42]; /**< meh */ + reg32_t FCFG_BANK; /**< FMC flash configuration bank */ + reg32_t FCFG_WRAPPER; /**< FMC flash wrapper configuration */ + reg32_t FCFG_BNK_TYPE; /**< FMC flash bank type */ + reg32_t __reserved21; /**< meh */ + reg32_t FCFG_B0_START; /**< FMC flash bank 0 starting address */ + reg32_t FCFG_B1_START; /**< FMC flash bank 1 starting address */ + reg32_t FCFG_B2_START; /**< FMC flash bank 2 starting address */ + reg32_t FCFG_B3_START; /**< FMC flash bank 3 starting address */ + reg32_t FCFG_B4_START; /**< FMC flash bank 4 starting address */ + reg32_t FCFG_B5_START; /**< FMC flash bank 5 starting address */ + reg32_t FCFG_B6_START; /**< FMC flash bank 6 starting address */ + reg32_t FCFG_B7_START; /**< FMC flash bank 7 starting address */ + reg32_t FCFG_B0_SSIZE0; /**< FMC flash bank 0 sector size */ +} flash_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define FLASH_BASEADDR 0x40030000 /**< base address of FLASH memory */ +/*@}*/ + +#define FLASH ((flash_regs_t *)(FLASH_BASEADDR + 0x4)) /**< FLASH register bank */ + + +/** + * VIMS registers + */ +typedef struct { + reg32_t STAT; /**< status */ + reg32_t CTL; /**< control */ +} vims_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define VIMS_BASE 0x40034000 /**< base address of VIMS memory */ +/*@}*/ + +#define VIMS ((vims_regs_t *)(VIMS_BASE + 0x4)) /**< VIMS register bank */ + +/** + * @brief VIMS register values + * @{ + */ +#define VIMS_CTL_STATS_CLR 0x80000000 +#define VIMS_CTL_STATS_CLR_m 0x80000000 + +#define VIMS_CTL_STATS_EN 0x40000000 +#define VIMS_CTL_STATS_EN_m 0x40000000 + +#define VIMS_CTL_DYN_CG_EN 0x20000000 +#define VIMS_CTL_DYN_CG_EN_m 0x20000000 + +#define VIMS_CTL_IDCODE_LB_DIS 0x00000020 +#define VIMS_CTL_IDCODE_LB_DIS_m 0x00000020 + +#define VIMS_CTL_SYSBUS_LB_DIS 0x00000010 +#define VIMS_CTL_SYSBUS_LB_DIS_m 0x00000010 + +#define VIMS_CTL_ARB_CFG 0x00000008 +#define VIMS_CTL_ARB_CFG_m 0x00000008 + +#define VIMS_CTL_PREF_EN 0x00000004 +#define VIMS_CTL_PREF_EN_m 0x00000004 + +#define VIMS_CTL_MODE_GPRAM 0x00000000 +#define VIMS_CTL_MODE_CACHE 0x00000001 +#define VIMS_CTL_MODE_SPLIT 0x00000002 +#define VIMS_CTL_MODE_OFF 0x00000003 +#define VIMS_CTL_MODE_m 0x00000003 +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* CC26x0_VIMS_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cc26x0_wdt.h b/cpu/cc26x0/include/cc26x0_wdt.h new file mode 100644 index 0000000000..3137adca9a --- /dev/null +++ b/cpu/cc26x0/include/cc26x0_wdt.h @@ -0,0 +1,56 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0_definitions + * @{ + * + * @file + * @brief CC26x0 WDT register definitions + */ + +#ifndef CC26x0_WDT_H +#define CC26x0_WDT_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * WDT registers + */ +typedef struct { + reg32_t LOAD; /**< config */ + reg32_t VALUE; /**< current count value */ + reg32_t CTL; /**< control */ + reg32_t ICR; /**< interrupt clear */ + reg32_t RIS; /**< raw interrupt status */ + reg32_t MIS; /**< masked interrupt status */ + reg32_t TEST; /**< test mode */ + reg32_t INT_CAUS; /**< interrupt cause test mode */ + reg32_t LOCK; /**< lock */ +} wdt_regs_t; + +/** @ingroup cpu_specific_peripheral_memory_map + * @{ + */ +#define WDT_BASE 0x40080000 /**< WDT base address */ +/*@}*/ + +#define WDT ((wdt_regs_t *) (WDT_BASE)) /**< WDT register bank */ + +#ifdef __cplusplus +} /* end extern "C" */ +#endif + +#endif /* CC26x0_WDT_H */ + +/*@}*/ diff --git a/cpu/cc26x0/include/cpu_conf.h b/cpu/cc26x0/include/cpu_conf.h new file mode 100644 index 0000000000..251e647c1d --- /dev/null +++ b/cpu/cc26x0/include/cpu_conf.h @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief Implementation specific CPU configuration options + * + * @author Leon M. George + * + */ + +#ifndef CPU_CONF_H +#define CPU_CONF_H + +#include "cpu_conf_common.h" + +#include "cc26x0.h" + +#include "cc26x0_aux.h" +#include "cc26x0_ccfg.h" +#include "cc26x0_fcfg.h" +#include "cc26x0_gpio.h" +#include "cc26x0_gpt.h" +#include "cc26x0_i2c.h" +#include "cc26x0_ioc.h" +#include "cc26x0_prcm.h" +#include "cc26x0_uart.h" +#include "cc26x0_vims.h" +#include "cc26x0_wdt.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief ARM Cortex-M specific CPU configuration + * @{ + */ +#define CPU_DEFAULT_IRQ_PRIO (1U) +#define CPU_IRQ_NUMOF IRQN_COUNT +#define CPU_FLASH_BASE FLASH_BASE +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* CPU_CONF_H */ +/** @} */ diff --git a/cpu/cc26x0/include/periph_cpu.h b/cpu/cc26x0/include/periph_cpu.h new file mode 100644 index 0000000000..4c18cc0b8b --- /dev/null +++ b/cpu/cc26x0/include/periph_cpu.h @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief CPU specific definitions for internal peripheral handling + * + * @author Leon M. George + */ + +#ifndef PERIPH_CPU_H_ +#define PERIPH_CPU_H_ + +#include "cpu.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Length of the CPU_ID in octets + */ +#define CPUID_LEN (16U) + +/** + * @brief Override GPIO mode values + */ +#define HAVE_GPIO_MODE_T +typedef enum { + GPIO_IN = (IOCFG_INPUT_ENABLE | IOCFG_PULLCTL_OFF), /**< input w/o pull R */ + GPIO_IN_PD = (IOCFG_INPUT_ENABLE | IOCFG_PULLCTL_DOWN), /**< input with pull-down */ + GPIO_IN_PU = (IOCFG_INPUT_ENABLE | IOCFG_PULLCTL_UP), /**< input with pull-up */ + GPIO_OUT = (IOCFG_PULLCTL_OFF), /**< push-pull output */ + GPIO_OD = (IOCFG_IOMODE_OPEN_DRAIN | IOCFG_PULLCTL_OFF), /**< open-drain w/o pull R */ + GPIO_OD_PU = (IOCFG_IOMODE_OPEN_DRAIN | IOCFG_PULLCTL_UP) /**< open-drain with pull-up */ +} gpio_mode_t; + +/** + * @brief Override GPIO flank values + */ +#define HAVE_GPIO_FLANK_T +typedef enum { + GPIO_FALLING = IOCFG_EDGEDET_FALLING, + GPIO_RISING = IOCFG_EDGEDET_RISING, + GPIO_BOTH = IOCFG_EDGEDET_BOTH +} gpio_flank_t; + +/** + * @brief Timer configuration options + */ +typedef struct { + gpt_reg_t *dev; /**< the GPT base address */ + uint8_t num; /**< number of the timer */ + uint8_t irqn; /**< interrupt number */ +} timer_conf_t; + +#ifdef __cplusplus +} +#endif + +#endif /* PERIPH_CPU_H_ */ +/** @} */ diff --git a/cpu/cc26x0/ldscripts/cc26x0f128.ld b/cpu/cc26x0/ldscripts/cc26x0f128.ld new file mode 100644 index 0000000000..624d92f567 --- /dev/null +++ b/cpu/cc26x0/ldscripts/cc26x0f128.ld @@ -0,0 +1,19 @@ +/** + * @addtogroup cpu_cc26x0 + * @{ + * + * @file + * @brief linker script for cc26x0f128 MCUs + * + * @} + */ + +/* Memory Space Definitions: */ +MEMORY +{ + rom (rx ) : ORIGIN = 0x00000000, LENGTH = 0x00020000 - 88 /* technically, it's 128K */ + gpram (rwx) : ORIGIN = 0x11000000, LENGTH = 8K /* configurable as cache. 20K here, 8K there, and 2K in the ld-script of cc26x0ware */ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K /* sram */ +} + +INCLUDE cortexm_base.ld diff --git a/cpu/cc26x0/lpm_arch.c b/cpu/cc26x0/lpm_arch.c new file mode 100644 index 0000000000..62752b187e --- /dev/null +++ b/cpu/cc26x0/lpm_arch.c @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief implementation of the kernels power management interface + * + * @} + */ + +#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) +{ +} diff --git a/cpu/cc26x0/periph/Makefile b/cpu/cc26x0/periph/Makefile new file mode 100644 index 0000000000..48422e909a --- /dev/null +++ b/cpu/cc26x0/periph/Makefile @@ -0,0 +1 @@ +include $(RIOTBASE)/Makefile.base diff --git a/cpu/cc26x0/periph/cpuid.c b/cpu/cc26x0/periph/cpuid.c new file mode 100644 index 0000000000..343c661bfb --- /dev/null +++ b/cpu/cc26x0/periph/cpuid.c @@ -0,0 +1,28 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief cpuid implementation for the CC26x0 + * + * @author Leon M. George + * + * @} + */ + +#include + +#include "periph/cpuid.h" + +void cpuid_get(void *id) +{ + memcpy(id, (void *) &FCFG->MAC_BLE_0, CPUID_LEN); +} diff --git a/cpu/cc26x0/periph/gpio.c b/cpu/cc26x0/periph/gpio.c new file mode 100644 index 0000000000..b277af8c58 --- /dev/null +++ b/cpu/cc26x0/periph/gpio.c @@ -0,0 +1,134 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief Low-level GPIO driver implementation + * + * @author Leon M. George + * + * @} + */ + +#include "cpu.h" +#include "sched.h" +#include "thread.h" +#include "periph/gpio.h" + +#define GPIO_ISR_CHAN_NUMOF (32) + +#define DOE_SHIFT (29U) + +/** + * @brief static callback memory + */ +static gpio_isr_ctx_t gpio_chan[GPIO_ISR_CHAN_NUMOF]; + +int gpio_init(gpio_t pin, gpio_mode_t mode) +{ + if ((pin < 0) || (pin > 31)) + return -1; + + /* enable GPIO clock */ + PRCM->PDCTL0 |= PDCTL0_PERIPH_ON; + while(!(PRCM->PDSTAT0 & PDSTAT0_PERIPH_ON)) ; + PRCM->GPIOCLKGR |= 1; + PRCM->CLKLOADCTL |= CLKLOADCTL_LOAD; + while (!(PRCM->CLKLOADCTL & CLKLOADCTL_LOADDONE)) ; + + /* configure the GPIO mode */ + IOC->CFG[pin] = mode; + GPIO->DOE &= ~(1 << pin); + GPIO->DOE |= ((~(mode >> DOE_SHIFT) & 0x1) << pin); + GPIO->DOUTCLR = (1 << pin); + + return 0; +} + +int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank, + gpio_cb_t cb, void *arg) +{ + int init = gpio_init(pin, mode); + if (init != 0) + return init; + + NVIC_EnableIRQ(EDGE_DETECT_IRQN); + + IOC->CFG[pin] |= flank; + + gpio_chan[pin].cb = cb; + gpio_chan[pin].arg = arg; + + /* clears the interrupt flag */ + GPIO->EVFLAGS |= (1 << pin); + + gpio_irq_enable(pin); + + return 0; +} + +void gpio_irq_enable(gpio_t pin) +{ + IOC->CFG[pin] |= IOCFG_EDGEIRQ_ENABLE; +} + +void gpio_irq_disable(gpio_t pin) +{ + IOC->CFG[pin] &= ~IOCFG_EDGEIRQ_ENABLE; +} + +int gpio_read(gpio_t pin) +{ + if (GPIO->DOE & (1 << pin)) { + return (GPIO->DOUT >> pin) & 1; + } + else { + return (GPIO->DIN >> pin) & 1; + } +} + +void gpio_set(gpio_t pin) +{ + GPIO->DOUTSET = (1 << pin); +} + +void gpio_clear(gpio_t pin) +{ + GPIO->DOUTCLR = (1 << pin); +} + +void gpio_toggle(gpio_t pin) +{ + GPIO->DOUTTGL = (1 << pin); +} + +void gpio_write(gpio_t pin, int value) +{ + if (value) { + GPIO->DOUTSET = (1 << pin); + } else { + GPIO->DOUTCLR = (1 << pin); + } +} + +void isr_edge(void) +{ + for (unsigned pin = 0; pin < GPIO_ISR_CHAN_NUMOF; pin++) { + /* doc claims EVFLAGS will only be set for pins that have edge detection enabled */ + if (GPIO->EVFLAGS & (1 << pin)) { + GPIO->EVFLAGS |= (1 << pin); + gpio_chan[pin].cb(gpio_chan[pin].arg); + } + } + if (sched_context_switch_request) { + thread_yield(); + } +} diff --git a/cpu/cc26x0/periph/timer.c b/cpu/cc26x0/periph/timer.c new file mode 100644 index 0000000000..b3de31cbb8 --- /dev/null +++ b/cpu/cc26x0/periph/timer.c @@ -0,0 +1,178 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief Low-level timer driver implementation for the CC26x0 + * + * @author Leon M. George + * + * @} + */ + +#include +#include + +#include "cpu.h" +#include "sched.h" +#include "thread.h" +#include "periph_conf.h" +#include "periph/timer.h" + +/** + * @brief Allocate memory for the interrupt context + */ +static timer_isr_ctx_t ctx[TIMER_NUMOF]; + +/** + * @brief Get the GPT register base for a timer + * + * @param[in] tim index of the timer + * + * @return base address + */ +static inline gpt_reg_t *dev(tim_t tim) +{ + return timer_config[tim].dev; +} + +int timer_init(tim_t tim, unsigned long freq, timer_cb_t cb, void *arg) +{ + /* make sure given timer is valid */ + if (tim >= TIMER_NUMOF) { + return -1; + } + + /* enable the times clock */ + PRCM->GPTCLKGR |= (1 << timer_config[tim].num); + PRCM->CLKLOADCTL = CLKLOADCTL_LOAD; + while (!(PRCM->CLKLOADCTL & CLKLOADCTL_LOADDONE)) {} + + /* disable (and reset) timer */ + dev(tim)->CTL = 0; + + /* save context */ + ctx[tim].cb = cb; + ctx[tim].arg = arg; + + /* configure timer to 16-bit, periodic, up-counting */ + dev(tim)->CFG = GPT_CFG_16T; + dev(tim)->TAMR = (GPT_TXMR_TXMR_PERIODIC | GPT_TXMR_TXCDIR_UP | GPT_TXMR_TXMIE); + + /* set the timer speed */ + dev(tim)->TAPR = (RCOSC48M_FREQ / freq) - 1; + /* enable global timer interrupt and start the timer */ + timer_irq_enable(tim); + dev(tim)->CTL = GPT_CTL_TAEN; + + return 0; +} + +int timer_set(tim_t tim, int channel, unsigned int timeout) +{ + return timer_set_absolute(tim, channel, timer_read(tim) + timeout); +} + +int timer_set_absolute(tim_t tim, int channel, unsigned int value) +{ + if (channel != 0) { + return -1; + } + + dev(tim)->TAMATCHR = value; + dev(tim)->IMR |= GPT_IMR_TAMIM; + + return 0; +} + +int timer_clear(tim_t tim, int channel) +{ + if (channel != 0) { + return -1; + } + + dev(tim)->IMR &= ~(GPT_IMR_TAMIM); + + return 0; +} + +unsigned int timer_read(tim_t tim) +{ + return dev(tim)->TAV & 0xFFFF; +} + +void timer_stop(tim_t tim) +{ + dev(tim)->CTL = 0; +} + +void timer_start(tim_t tim) +{ + dev(tim)->CTL = GPT_CTL_TAEN; +} + +void timer_irq_enable(tim_t tim) +{ + NVIC_EnableIRQ(GPTIMER_0A_IRQN + (2 * timer_config[tim].num)); +} + +void timer_irq_disable(tim_t tim) +{ + NVIC_DisableIRQ(GPTIMER_0A_IRQN + (2 * timer_config[tim].num)); +} + +/** + * @brief handle interrupt for a timer + * + * @param[in] tim index of the timer + */ +static inline void isr_handler(tim_t tim) +{ + uint32_t mis = dev(tim)->MIS; + dev(tim)->ICLR = mis; + + if (mis & GPT_IMR_TAMIM) { + dev(tim)->IMR &= ~GPT_IMR_TAMIM; + ctx[tim].cb(ctx[tim].arg, 0); + } + + if (sched_context_switch_request) { + thread_yield(); + } +} + +#ifdef TIMER_0_ISR +void TIMER_0_ISR(void) +{ + isr_handler(0); +} +#endif + +#ifdef TIMER_1_ISR +void TIMER_1_ISR(void) +{ + isr_handler(1); +} +#endif + +#ifdef TIMER_2_ISR +void TIMER_2_ISR(void) +{ + isr_handler(2); +} +#endif + +#ifdef TIMER_3_ISR +void TIMER_3_ISR(void) +{ + isr_handler(3); +} +#endif diff --git a/cpu/cc26x0/periph/uart.c b/cpu/cc26x0/periph/uart.c new file mode 100644 index 0000000000..dd4607497d --- /dev/null +++ b/cpu/cc26x0/periph/uart.c @@ -0,0 +1,137 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief Low-level UART driver implementation + * + * @author Leon M. George + * + * @} + */ + +#include "cpu.h" +#include "sched.h" +#include "thread.h" +#include "periph/uart.h" + +/** + * @brief Bit mask for the fractional part of the baudrate + */ +#define FRAC_BITS (6U) +#define FRAC_MASK (0x3f) + +/** + * @brief Get the enable mask depending on enabled HW flow control + */ +#if UART_HW_FLOW_CONTROL +#define ENABLE_MASK (UART_CTSEN | UART_CTL_RTSEN | \ + UART_CTL_RXE | UART_CTL_TXE | UART_CTL_UARTEN) +#else +#define ENABLE_MASK (UART_CTL_RXE | UART_CTL_TXE | UART_CTL_UARTEN) +#endif + +/** + * @brief allocate memory to store callback functions + */ +static uart_isr_ctx_t ctx[UART_NUMOF]; + + +int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) +{ + /* make sure the uart device is valid */ + if (uart != 0) { + return -1; + } + + /* enable clocks: serial power domain and UART */ + PRCM->PDCTL0SERIAL = 1; + while (!(PRCM->PDSTAT0 & PDSTAT0_SERIAL_ON)) ; + uart_poweron(uart); + + /* disable and reset the UART */ + UART->CTL = 0; + + /* save context */ + ctx[0].rx_cb = rx_cb; + ctx[0].arg = arg; + + /* configure pins */ + IOC->CFG[UART_TX_PIN] = IOCFG_PORTID_UART0_TX; + IOC->CFG[UART_RX_PIN] = (IOCFG_PORTID_UART0_RX | IOCFG_INPUT_ENABLE); +#if UART_HW_FLOW_CONTROL + IOC->CFG[UART_RTS_PIN] = IOCFG_PORTID_UART0_RTS; + IOC->CFG[UART_CTS_PIN] = (IOCFG_PORTID_UART0_CTS | IOCFG_INPUT_ENABLE); +#endif + + /* calculate baud-rate */ + uint32_t tmp = (CLOCK_CORECLOCK * 4); + tmp += (baudrate / 2); + tmp /= baudrate; + UART->IBRD = (tmp >> FRAC_BITS); + UART->FBRD = (tmp & FRAC_MASK); + + /* configure line to 8N1 mode, LRCH must be written after IBRD and FBRD! */ + UART->LCRH = UART_LCRH_WLEN_8; + + /* enable the RX interrupt */ + UART->IMSC = UART_IMSC_RXIM; + NVIC_EnableIRQ(UART0_IRQN); + + /* start the UART */ + UART->CTL = ENABLE_MASK; + + return 0; +} + +void uart_write(uart_t uart, const uint8_t *data, size_t len) +{ + for (size_t i = 0; i < len; i++) { + while (UART->FR & UART_FR_TXFF) {} + UART->DR = data[i]; + } +} + +void uart_poweron(uart_t uart) +{ + PRCM->UARTCLKGR = 1; + PRCM->CLKLOADCTL = CLKLOADCTL_LOAD; + while (!(PRCM->CLKLOADCTL & CLKLOADCTL_LOADDONE)) {} + + UART->CTL = ENABLE_MASK; +} + +void uart_poweroff(uart_t uart) +{ + UART->CTL = 0; + + PRCM->UARTCLKGR = 0; + PRCM->CLKLOADCTL = CLKLOADCTL_LOAD; + while (!(PRCM->CLKLOADCTL & CLKLOADCTL_LOADDONE)) {} + +} + +void isr_uart(void) +{ + /* remember pending interrupts */ + uint32_t mis = UART->MIS; + /* clear them */ + UART->ICR = mis; + + /* read received byte and pass it to the RX callback */ + if (mis & UART_MIS_RXMIS) { + ctx[0].rx_cb(ctx[0].arg, (uint8_t)UART->DR); + } + + if (sched_context_switch_request) { + thread_yield(); + } +} diff --git a/cpu/cc26x0/vectors.c b/cpu/cc26x0/vectors.c new file mode 100644 index 0000000000..e4ef61258f --- /dev/null +++ b/cpu/cc26x0/vectors.c @@ -0,0 +1,132 @@ +/* + * Copyright (C) 2016 Leon George + * + * 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_cc26x0 + * @{ + * + * @file + * @brief Interrupt vector definitions + * + * @author Leon M. George + */ + +#include +#include "cpu.h" +#include "board.h" +#include "vectors_cortexm.h" + +/* get the start of the ISR stack as defined in the linkerscript */ +extern uint32_t _estack; + +/* define a local dummy handler as it needs to be in the same compilation unit + * as the alias definition */ +void dummy_handler(void) { + dummy_handler_default(); +} + +/* Cortex-M common interrupt vectors */ +WEAK_DEFAULT void isr_svc(void); +WEAK_DEFAULT void isr_pendsv(void); +WEAK_DEFAULT void isr_systick(void); +/* CC26x0 specific interrupt vectors */ +WEAK_DEFAULT void isr_edge(void); +WEAK_DEFAULT void isr_i2c(void); +WEAK_DEFAULT void isr_rfc_cpe1(void); +WEAK_DEFAULT void isr_aon_rx_tx_cs(void); +WEAK_DEFAULT void isr_aon_rtc(void); +WEAK_DEFAULT void isr_uart(void); +WEAK_DEFAULT void isr_scse0_aon(void); +WEAK_DEFAULT void isr_ssi0(void); +WEAK_DEFAULT void isr_ssi1(void); +WEAK_DEFAULT void isr_rfc_cpe0(void); +WEAK_DEFAULT void isr_rfc_hw(void); +WEAK_DEFAULT void isr_rfc_cmd_ack(void); +WEAK_DEFAULT void isr_i2s(void); +WEAK_DEFAULT void isr_scse1_aon(void); +WEAK_DEFAULT void isr_watchdog(void); +WEAK_DEFAULT void isr_timer0_chan0(void); +WEAK_DEFAULT void isr_timer0_chan1(void); +WEAK_DEFAULT void isr_timer1_chan0(void); +WEAK_DEFAULT void isr_timer1_chan1(void); +WEAK_DEFAULT void isr_timer2_chan0(void); +WEAK_DEFAULT void isr_timer2_chan1(void); +WEAK_DEFAULT void isr_timer3_chan0(void); +WEAK_DEFAULT void isr_timer3_chan1(void); +WEAK_DEFAULT void isr_crypto_res(void); +WEAK_DEFAULT void isr_dma(void); +WEAK_DEFAULT void isr_dmaerr(void); +WEAK_DEFAULT void isr_flash(void); +WEAK_DEFAULT void isr_se0(void); +WEAK_DEFAULT void isr_aux_ce(void); +WEAK_DEFAULT void isr_aon_prog(void); +WEAK_DEFAULT void isr_dyn_prog(void); +WEAK_DEFAULT void isr_comp(void); +WEAK_DEFAULT void isr_adc(void); +WEAK_DEFAULT void isr_trng(void); + +/* interrupt vector table */ +ISR_VECTORS const void *interrupt_vector[] = { + /* Exception stack pointer */ + (void *) (&_estack), /* pointer to the top of the stack */ + /* Cortex-M3 handlers */ + (void *) reset_handler_default, /* entry point of the program */ + (void *) nmi_default, /* non maskable interrupt handler */ + (void *) hard_fault_default, /* hard fault exception */ + (void *) mem_manage_default, /* memory manage exception */ + (void *) bus_fault_default, /* bus fault exception */ + (void *) usage_fault_default, /* usage fault exception */ + NULL, /* reserved */ + NULL, /* reserved */ + NULL, /* reserved */ + NULL, /* reserved */ + (void *) isr_svc, /* system call interrupt, in RIOT used for + * switching into thread context on boot */ + (void *) debug_mon_default, /* debug monitor exception */ + NULL, /* reserved */ + (void *) isr_pendsv, /* pendSV interrupt, in RIOT the actual + * context switching is happening here */ + (void *) isr_systick, /* SysTick interrupt, not used in RIOT */ + /* CC26x0 specific peripheral handlers */ + (void *) isr_edge, /* 16 AON edge detect */ + (void *) isr_i2c, /* 17 I2C */ + (void *) isr_rfc_cpe1, /* 18 RF Command and Packet Engine 1 */ + (void *) isr_aon_rx_tx_cs, /* 19 AON SpiSplave Rx, Tx and CS */ + (void *) isr_aon_rtc, /* 20 AON RTC */ + (void *) isr_uart, /* 21 UART0 Rx and Tx */ + (void *) isr_scse0_aon, /* 22 Sensor Controller software event 0, through AON domain */ + (void *) isr_ssi0, /* 23 SSI0 Rx and Tx */ + (void *) isr_ssi1, /* 24 SSI1 Rx and Tx */ + (void *) isr_rfc_cpe0, /* 25 RF Command and Packet Engine 0 */ + (void *) isr_rfc_hw, /* 26 RF Core Hardware */ + (void *) isr_rfc_cmd_ack, /* 27 RF Core Command Acknowledge */ + (void *) isr_i2s, /* 28 I2S */ + (void *) isr_scse1_aon, /* 29 Sensor Controller software event 1, through AON domain */ + (void *) isr_watchdog, /* 30 Watchdog timer */ + (void *) isr_timer0_chan0, /* 31 Timer 0 subtimer A */ + (void *) isr_timer0_chan1, /* 32 Timer 0 subtimer B */ + (void *) isr_timer1_chan0, /* 33 Timer 1 subtimer A */ + (void *) isr_timer1_chan1, /* 34 Timer 1 subtimer B */ + (void *) isr_timer2_chan0, /* 35 Timer 2 subtimer A */ + (void *) isr_timer2_chan1, /* 36 Timer 2 subtimer B */ + (void *) isr_timer3_chan0, /* 37 Timer 3 subtimer A */ + (void *) isr_timer3_chan1, /* 38 Timer 3 subtimer B */ + (void *) isr_crypto_res, /* 39 Crypto Core Result available */ + (void *) isr_dma, /* 40 uDMA Software */ + (void *) isr_dmaerr, /* 41 uDMA Error */ + (void *) isr_flash, /* 42 Flash controller */ + (void *) isr_se0, /* 43 Software Event 0 */ + (void *) isr_aux_ce, /* 44 AUX combined event, directly to MCU domain */ + (void *) isr_aon_prog, /* 45 AON programmable 0 */ + (void *) isr_dyn_prog, /* 46 Dynamic Programmable interrupt (default source: PRCM) */ + (void *) isr_comp, /* 47 AUX Comparator A */ + (void *) isr_adc, /* 48 AUX ADC IRQ */ + (void *) isr_trng, /* 49 TRNG event */ +}; + +/** @} */ diff --git a/examples/gnrc_border_router/Makefile b/examples/gnrc_border_router/Makefile index 6e17659aa9..ec86a1159e 100644 --- a/examples/gnrc_border_router/Makefile +++ b/examples/gnrc_border_router/Makefile @@ -7,7 +7,7 @@ BOARD ?= samr21-xpro # This has to be the absolute path to the RIOT base directory: RIOTBASE ?= $(CURDIR)/../.. -BOARD_INSUFFICIENT_MEMORY := airfy-beacon msb-430 msb-430h pca10000 pca10005 \ +BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk msb-430 msb-430h pca10000 pca10005 \ nrf51dongle nrf6310 nucleo-f103 nucleo-f334 \ spark-core stm32f0discovery telosb \ weio wsn430-v1_3b wsn430-v1_4 yunjia-nrf51822 z1 nucleo-f072 diff --git a/tests/thread_cooperation/Makefile b/tests/thread_cooperation/Makefile index e88fec965b..301cfab5ca 100644 --- a/tests/thread_cooperation/Makefile +++ b/tests/thread_cooperation/Makefile @@ -1,7 +1,7 @@ APPLICATION = thread_cooperation include ../Makefile.tests_common -BOARD_INSUFFICIENT_MEMORY := chronos msb-430 msb-430h mbed_lpc1768 \ +BOARD_INSUFFICIENT_MEMORY := cc2650stk chronos msb-430 msb-430h mbed_lpc1768 \ stm32f0discovery pca10000 pca10005 \ yunjia-nrf51822 spark-core airfy-beacon nucleo-f103 \ nucleo-f334 nrf51dongle nrf6310 weio nucleo-f072 diff --git a/tests/unittests/Makefile b/tests/unittests/Makefile index ac0b1dba0e..80c9dba7d6 100644 --- a/tests/unittests/Makefile +++ b/tests/unittests/Makefile @@ -1,7 +1,7 @@ APPLICATION = unittests include ../Makefile.tests_common -BOARD_INSUFFICIENT_MEMORY := airfy-beacon chronos msb-430 msb-430h pca10000 \ +BOARD_INSUFFICIENT_MEMORY := airfy-beacon cc2650stk chronos msb-430 msb-430h pca10000 \ pca10005 spark-core stm32f0discovery \ telosb wsn430-v1_3b wsn430-v1_4 z1 nucleo-f103 \ nucleo-f334 yunjia-nrf51822 samr21-xpro \