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

Merge pull request #4746 from haukepetersen/add_board_nrf52dk

cpu/boards: added support for nRF52 DK
This commit is contained in:
Hauke Petersen 2016-02-05 15:11:57 +01:00
commit 5165e48399
27 changed files with 16834 additions and 1 deletions

3
boards/nrf52dk/Makefile Normal file
View File

@ -0,0 +1,3 @@
MODULE = board
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,3 @@
ifneq (,$(filter saul_default,$(USEMODULE)))
USEMODULE += saul_gpio
endif

View File

@ -0,0 +1,13 @@
# Put defined MCU peripherals here (in alphabetical order)
FEATURES_PROVIDED += periph_cpuid
FEATURES_PROVIDED += periph_gpio
FEATURES_PROVIDED += periph_random
FEATURES_PROVIDED += periph_rtt
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_m4_2

View File

@ -0,0 +1,20 @@
# define the cpu used by the nRF52 DK
export CPU = nrf52
export CPU_MODEL = nrf52xxaa
# set default port depending on operating system
PORT_LINUX ?= /dev/ttyACM0
PORT_DARWIN ?= $(shell ls -1 /dev/tty.usbmodem* | head -n 1)
# setup the boards dependencies
include $(RIOTBOARD)/$(BOARD)/Makefile.dep
# setup JLink for flashing
export JLINK_DEVICE := nrf52
include $(RIOTBOARD)/Makefile.include.jlink
# setup serial terminal
include $(RIOTBOARD)/Makefile.include.serial
# include cortex defaults
include $(RIOTBOARD)/Makefile.include.cortexm_common

32
boards/nrf52dk/board.c Normal file
View File

@ -0,0 +1,32 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52dk
* @{
*
* @file
* @brief Board initialization for the nRF52 DK
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "board.h"
void board_init(void)
{
/* initialize the boards LEDs */
NRF_P0->DIRSET = (LED1_MASK | LED2_MASK | LED3_MASK | LED4_MASK);
NRF_P0->OUTSET = (LED1_MASK | LED2_MASK | LED3_MASK | LED4_MASK);
/* initialize the CPU */
cpu_init();
}

View File

@ -0,0 +1,79 @@
/*
* Copyright (C) 2016 Feie Universität Berlin
*
* 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_nrf52dk nRF52 DK
* @ingroup boards
* @{
*
* @file
* @brief Board specific configuaration for the nRF52 DK
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
*/
#ifndef BOARD_H
#define BOARD_H
#include "cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief LED pin configuration
* @{
*/
#define LED1_PIN (GPIO_PIN(0, 17))
#define LED2_PIN (GPIO_PIN(0, 18))
#define LED3_PIN (GPIO_PIN(0, 19))
#define LED4_PIN (GPIO_PIN(0, 20))
#define LED1_MASK (1 << 17)
#define LED2_MASK (1 << 18)
#define LED3_MASK (1 << 19)
#define LED4_MASK (1 << 20)
/** @} */
/**
* @brief RIOT LED macros for backwards compatibility
* @{
*/
#define LED_RED_ON (NRF_P0->OUTSET = LED1_PIN)
#define LED_RED_OFF (NRF_P0->OUTCLR = LED2_PIN)
#define LED_RED_TOGGLE (NRF_P0->OUT ^= LED3_PIN)
#define LED_GREEN_ON (NRF_P0->OUTSET = LED1_PIN)
#define LED_GREEN_OFF (NRF_P0->OUTCLR = LED2_PIN)
#define LED_GREEN_TOGGLE (NRF_P0->OUT ^= LED3_PIN)
#define LED_ORANGE_ON (NRF_P0->OUTSET = LED1_PIN)
#define LED_ORANGE_OFF (NRF_P0->OUTCLR = LED2_PIN)
#define LED_ORANGE_TOGGLE (NRF_P0->OUT ^= LED3_PIN)
/** @} */
/**
* @brief Button pin configuration
* @{
*/
#define BUTTON1_PIN (GPIO_PIN(0, 13))
#define BUTTON2_PIN (GPIO_PIN(0, 14))
#define BUTTON3_PIN (GPIO_PIN(0, 15))
#define BUTTON4_PIN (GPIO_PIN(0, 16))
/** @} */
/**
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
*/
void board_init(void);
#ifdef __cplusplus
}
#endif
#endif /** BOARD_H */
/** @} */

View File

@ -0,0 +1,91 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52dk
* @{
*
* @file
* @brief Configuration of SAUL mapped GPIO pins
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
*/
#ifndef GPIO_PARAMS_H
#define GPIO_PARAMS_H
#include "board.h"
#include "saul/periph.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief LED configuration
*/
static const saul_gpio_params_t saul_gpio_params[] =
{
{
.name = "LED 1",
.pin = LED1_PIN,
.dir = GPIO_DIR_OUT,
.pull = GPIO_NOPULL
},
{
.name = "LED 2",
.pin = LED2_PIN,
.dir = GPIO_DIR_OUT,
.pull = GPIO_NOPULL
},
{
.name = "LED 3",
.pin = LED3_PIN,
.dir = GPIO_DIR_OUT,
.pull = GPIO_NOPULL
},
{
.name = "LED 4",
.pin = LED4_PIN,
.dir = GPIO_DIR_OUT,
.pull = GPIO_NOPULL
},
{
.name = "Button 1",
.pin = BUTTON1_PIN,
.dir = GPIO_DIR_IN,
.pull = GPIO_PULLUP
},
{
.name = "Button 2",
.pin = BUTTON2_PIN,
.dir = GPIO_DIR_IN,
.pull = GPIO_PULLUP
},
{
.name = "Button 3",
.pin = BUTTON3_PIN,
.dir = GPIO_DIR_IN,
.pull = GPIO_PULLUP
},
{
.name = "Button 4",
.pin = BUTTON4_PIN,
.dir = GPIO_DIR_IN,
.pull = GPIO_PULLUP
}
};
#ifdef __cplusplus
}
#endif
#endif /* GPIO_PARAMS_H */
/** @} */

View File

@ -0,0 +1,88 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52dk
* @{
*
* @file
* @brief Peripheral configuration for the nRF52 DK
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
*/
#ifndef PERIPH_CONF_H
#define PERIPH_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Clock configuration
*
* @note The radio will not work with the internal RC oscillator!
*
* @{
*/
#define CLOCK_CORECLOCK (64000000U) /* fixed for all NRF52832 */
#define CLOCK_CRYSTAL (32U) /* set to 0: internal RC oscillator
32: 32MHz crystal */
/** @} */
/**
* @brief Timer configuration
* @{
*/
#define TIMER_NUMOF (1U)
#define TIMER_0_EN 1
/* Timer 0 configuration */
#define TIMER_0_DEV NRF_TIMER0
#define TIMER_0_CHANNELS 3
#define TIMER_0_MAX_VALUE (0xffffffff)
#define TIMER_0_BITMODE TIMER_BITMODE_BITMODE_32Bit
#define TIMER_0_ISR isr_timer0
#define TIMER_0_IRQ TIMER0_IRQn
/** @} */
/**
* @brief Real time counter configuration
* @{
*/
#define RTT_NUMOF (1U)
#define RTT_DEV NRF_RTC0
#define RTT_IRQ RTC0_IRQn
#define RTT_ISR isr_rtc0
#define RTT_MAX_VALUE (0xffffff)
#define RTT_FREQUENCY (10) /* in Hz */
#define RTT_PRESCALER (3275U) /* run with 10 Hz */
/** @} */
/**
* @brief UART configuration
* @{
*/
#define UART_NUMOF (1U)
#define UART_PIN_RX 8
#define UART_PIN_TX 6
/** @} */
/**
* @name Random Number Generator configuration
* @{
*/
#define RANDOM_NUMOF (1U)
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* __PERIPH_CONF_H */

7
cpu/nrf52/Makefile Normal file
View File

@ -0,0 +1,7 @@
# define the module that is build
MODULE = cpu
# add a list of subdirectories, that should also be build
DIRS = periph $(RIOTCPU)/cortexm_common
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,3 @@
export CPU_ARCH = cortex-m4f
include $(RIOTCPU)/Makefile.include.cortexm_common

112
cpu/nrf52/cpu.c Normal file
View File

@ -0,0 +1,112 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the CPU initialization
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
/* FTPAN helper functions */
static bool ftpan_32(void);
static bool ftpan_37(void);
static bool ftpan_36(void);
/**
* @brief Initialize the CPU, set IRQ priorities
*/
void cpu_init(void)
{
/* set pendSV interrupt to lowest possible priority */
NVIC_SetPriority(PendSV_IRQn, 0xff);
/* Workaround for FTPAN-32
* "DIF: Debug session automatically enables TracePort pins." */
if (ftpan_32()) {
CoreDebug->DEMCR &= ~CoreDebug_DEMCR_TRCENA_Msk;
}
/* Workaround for FTPAN-37
* "AMLI: EasyDMA is slow with Radio, ECB, AAR and CCM." */
if (ftpan_37()) {
*(volatile uint32_t *)0x400005A0 = 0x3;
}
/* Workaround for FTPAN-36
* "CLOCK: Some registers are not reset when expected." */
if (ftpan_36()) {
NRF_CLOCK->EVENTS_DONE = 0;
NRF_CLOCK->EVENTS_CTTO = 0;
}
/* set the correct clock source for HFCLK */
#if (CLOCK_CRYSTAL == 32)
NRF_CLOCK->LFCLKSRC = (CLOCK_LFCLKSRC_SRC_Xtal << CLOCK_LFCLKSRC_SRC_Pos);
NRF_CLOCK->EVENTS_HFCLKSTARTED = 0;
NRF_CLOCK->TASKS_HFCLKSTART = 1;
while (NRF_CLOCK->EVENTS_HFCLKSTARTED == 0);
#endif
}
/**
* @brief Check workaround for FTPAN-32
*/
static bool ftpan_32(void)
{
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x6)
&& (((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30)
&& (((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true;
}
}
return false;
}
/**
* @brief Check workaround for FTPAN-36
*/
static bool ftpan_36(void)
{
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x6)
&& (((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30)
&& (((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true;
}
}
return false;
}
/**
* @brief Check workaround for FTPAN-37
*/
static bool ftpan_37(void)
{
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x6)
&& (((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30)
&& (((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true;
}
}
return false;
}

View File

@ -0,0 +1,49 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief nRF52 specific CPU configuration
*
* @author Hauke Petersen <hauke.peterse@fu-berlin.de>
*
*/
#ifndef CPU_CONF_H
#define CPU_CONF_H
#include "nrf52.h"
#include "nrf52_bitfields.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief ARM Cortex-M specific CPU configuration
* @{
*/
#define CPU_DEFAULT_IRQ_PRIO (1U)
#define CPU_IRQ_NUMOF (38)
#define CPU_FLASH_BASE (0x00000000)
/** @} */
/**
* @brief CPU_ID length in octets
*/
#define CPUID_ID_LEN (8)
#ifdef __cplusplus
}
#endif
#endif /* CPU_CONF_H */
/** @} */

2749
cpu/nrf52/include/nrf52.h Normal file

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,64 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief CPU specific definitions for handling peripherals
*
* @author Hauke Petersen <hauke.peterse@fu-berlin.de>
*/
#ifndef CPU_PERIPH_H
#define CPU_PERIPH_H
#include "cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Override GPIO pull register select values
* @{
*/
#define HAVE_GPIO_PP_T
typedef enum {
GPIO_NOPULL = 0, /**< do not use internal pull resistors */
GPIO_PULLUP = 3, /**< enable internal pull-up resistor */
GPIO_PULLDOWN = 1 /**< enable internal pull-down resistor */
} gpio_pp_t;
/** @} */
/**
* @brief Override GPIO active flank values
* @{
*/
#define HAVE_GPIO_FLANK_T
typedef enum {
GPIO_FALLING = 2, /**< emit interrupt on falling flank */
GPIO_RISING = 1, /**< emit interrupt on rising flank */
GPIO_BOTH = 3 /**< emit interrupt on both flanks */
} gpio_flank_t;
/** @} */
/**
* @brief Override macro for defining GPIO pins
*
* The port definition is used (and zeroed) to suppress compiler warnings
*/
#define GPIO_PIN(x,y) ((x & 0) | y)
#ifdef __cplusplus
}
#endif
#endif /* CPU_PERIPH_H */
/** @} */

View File

@ -0,0 +1,27 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Memory definitions for the NRF52832XXAA
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x00000000, LENGTH = 512K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
}
INCLUDE cortexm_base.ld

72
cpu/nrf52/lpm_arch.c Normal file
View File

@ -0,0 +1,72 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the kernels power management interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include "cpu.h"
#include "arch/lpm_arch.h"
void lpm_arch_init(void)
{
/* TODO: needs to be implemented */
}
enum lpm_mode lpm_arch_set(enum lpm_mode target)
{
switch (target) {
/* wait for next interrupt */
case LPM_IDLE:
case LPM_SLEEP:
case LPM_POWERDOWN:
__DSB();
__WFI();
break;
case LPM_OFF:
NRF_POWER->SYSTEMOFF = 1;
break;
/* do nothing here */
case LPM_UNKNOWN:
case LPM_ON:
default:
break;
}
return 0;
}
enum lpm_mode lpm_arch_get(void)
{
/* TODO: needs to be implemented */
return 0;
}
void lpm_arch_awake(void)
{
/* TODO: needs to be implemented */
}
void lpm_arch_begin_awake(void)
{
/* TODO: needs to be implemented */
}
void lpm_arch_end_awake(void)
{
/* TODO: needs to be implemented */
}

View File

@ -0,0 +1,3 @@
MODULE = periph
include $(RIOTBASE)/Makefile.base

34
cpu/nrf52/periph/cpuid.c Normal file
View File

@ -0,0 +1,34 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief CPUID interface implementation
*
* The NRF52832 provides a 64-bit unique identifier, that is unique for each
* shipped unit.
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include <string.h>
#include "cpu.h"
#include "cpu_conf.h"
void cpuid_get(void *id)
{
memcpy(id, (void *)NRF_FICR->DEVICEID, CPUID_ID_LEN);
}

125
cpu/nrf52/periph/gpio.c Normal file
View File

@ -0,0 +1,125 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Low-level GPIO driver implementation
*
* NOTE: this GPIO driver implementation supports due to hardware limitations
* only one pin configured as external interrupt source at a time!
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include "cpu.h"
#include "sched.h"
#include "thread.h"
#include "periph/gpio.h"
#include "periph_conf.h"
/**
* @brief Place to store the interrupt context
*/
static gpio_isr_ctx_t exti_chan;
int gpio_init(gpio_t pin, gpio_dir_t dir, gpio_pp_t pullup)
{
/* configure pin direction, input buffer and pull resistor state */
NRF_P0->PIN_CNF[pin] = ((dir << GPIO_PIN_CNF_DIR_Pos) |
(dir << GPIO_PIN_CNF_INPUT_Pos) |
(pullup << GPIO_PIN_CNF_PULL_Pos));
printf("cfg[%i] 0x%08x\n", (int)pin, (unsigned)NRF_P0->PIN_CNF[pin]);
return 0;
}
int gpio_init_int(gpio_t pin, gpio_pp_t pullup, gpio_flank_t flank,
gpio_cb_t cb, void *arg)
{
/* disable external interrupt in case one is active */
NRF_GPIOTE->INTENSET &= ~(GPIOTE_INTENSET_IN0_Msk);
/* save callback */
exti_chan.cb = cb;
exti_chan.arg = arg;
/* configure pin as input */
gpio_init(pin, GPIO_DIR_IN, pullup);
/* set interrupt priority and enable global GPIOTE interrupt */
NVIC_EnableIRQ(GPIOTE_IRQn);
/* configure the GPIOTE channel: set even mode, pin and active flank */
NRF_GPIOTE->CONFIG[0] = (GPIOTE_CONFIG_MODE_Event |
(pin << GPIOTE_CONFIG_PSEL_Pos) |
(flank << GPIOTE_CONFIG_POLARITY_Pos));
/* enable external interrupt */
NRF_GPIOTE->INTENSET |= GPIOTE_INTENSET_IN0_Msk;
return 0;
}
void gpio_irq_enable(gpio_t pin)
{
(void) pin;
NRF_GPIOTE->INTENSET |= GPIOTE_INTENSET_IN0_Msk;
}
void gpio_irq_disable(gpio_t pin)
{
(void) pin;
NRF_GPIOTE->INTENCLR |= GPIOTE_INTENSET_IN0_Msk;
}
int gpio_read(gpio_t pin)
{
if (NRF_P0->DIR & (1 << pin)) {
return (NRF_P0->OUT & (1 << pin)) ? 1 : 0;
}
else {
return (NRF_P0->IN & (1 << pin)) ? 1 : 0;
}
}
void gpio_set(gpio_t pin)
{
NRF_P0->OUTSET = (1 << pin);
}
void gpio_clear(gpio_t pin)
{
NRF_P0->OUTCLR = (1 << pin);
}
void gpio_toggle(gpio_t pin)
{
NRF_P0->OUT ^= (1 << pin);
}
void gpio_write(gpio_t pin, int value)
{
if (value) {
NRF_P0->OUTSET = (1 << pin);
} else {
NRF_P0->OUTCLR = (1 << pin);
}
}
void isr_gpiote(void)
{
if (NRF_GPIOTE->EVENTS_IN[0] == 1) {
NRF_GPIOTE->EVENTS_IN[0] = 0;
exti_chan.cb(exti_chan.arg);
}
if (sched_context_switch_request) {
thread_yield();
}
}

58
cpu/nrf52/periph/random.c Normal file
View File

@ -0,0 +1,58 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the random number generator interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include "cpu.h"
#include "periph_conf.h"
#include "periph/random.h"
void random_init(void)
{
/* nothing to do here */
}
int random_read(char *buf, unsigned int num)
{
unsigned int count = 0;
NRF_RNG->TASKS_START = 1;
while (count < num) {
while (NRF_RNG->EVENTS_VALRDY == 0);
NRF_RNG->EVENTS_VALRDY = 0;
buf[count++] = (char)NRF_RNG->VALUE;
}
NRF_RNG->TASKS_STOP = 1;
return count;
}
void random_poweron(void)
{
/* nothing to do here */
}
void random_poweroff(void)
{
/* nothing to do here */
}

131
cpu/nrf52/periph/rtt.c Normal file
View File

@ -0,0 +1,131 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the peripheral real-time timer interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include <stdlib.h>
#include "cpu.h"
#include "board.h"
#include "sched.h"
#include "thread.h"
#include "periph_conf.h"
#include "periph/rtt.h"
/*
* @brief Callback for the active alarm
*/
static rtt_cb_t alarm_cb;
/**
* @brief Argument for the active alarm callback
*/
static void *alarm_arg;
/**
* @brief Callback for the overflow event
*/
static rtt_cb_t overflow_cb;
/**
* @brief Argument for the overflow callback
*/
static void *overflow_arg;
void rtt_init(void)
{
/* configure interrupt */
NVIC_EnableIRQ(RTT_IRQ);
/* set prescaler */
RTT_DEV->PRESCALER = RTT_PRESCALER;
/* enable the low-frequency clock */
NRF_CLOCK->TASKS_LFCLKSTART = 1;
/* start the actual RTT thing */
RTT_DEV->TASKS_START = 1;
}
void rtt_set_overflow_cb(rtt_cb_t cb, void *arg)
{
overflow_cb = cb;
overflow_arg = arg;
RTT_DEV->INTENSET = RTC_INTENSET_OVRFLW_Msk;
}
void rtt_clear_overflow_cb(void)
{
RTT_DEV->INTENCLR = RTC_INTENCLR_OVRFLW_Msk;
}
uint32_t rtt_get_counter(void)
{
return RTT_DEV->COUNTER;
}
void rtt_set_counter(uint32_t counter)
{
(void) counter;
/* not supported by the nRF52 */
}
void rtt_set_alarm(uint32_t alarm, rtt_cb_t cb, void *arg)
{
alarm_cb = cb;
alarm_arg = arg;
RTT_DEV->CC[0] = (alarm & RTT_MAX_VALUE);
RTT_DEV->INTENSET = RTC_INTENSET_COMPARE0_Msk;
}
uint32_t rtt_get_alarm(void)
{
return RTT_DEV->CC[0];
}
void rtt_clear_alarm(void)
{
RTT_DEV->INTENCLR = RTC_INTENSET_COMPARE0_Msk;
}
void rtt_poweron(void)
{
RTT_DEV->TASKS_START = 1;
}
void rtt_poweroff(void)
{
RTT_DEV->TASKS_STOP = 1;
}
void RTT_ISR(void)
{
if (RTT_DEV->EVENTS_COMPARE[0] == 1) {
RTT_DEV->EVENTS_COMPARE[0] = 0;
RTT_DEV->INTENCLR = RTC_INTENSET_COMPARE0_Msk;
alarm_cb(alarm_arg);
}
if (RTT_DEV->EVENTS_OVRFLW == 1) {
RTT_DEV->EVENTS_OVRFLW = 0;
overflow_cb(overflow_arg);
}
if (sched_context_switch_request) {
thread_yield();
}
}

258
cpu/nrf52/periph/spi.c Normal file
View File

@ -0,0 +1,258 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the peripheral SPI interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Frank Holtz <frank-riot2015@holtznet.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include "cpu.h"
#include "mutex.h"
#include "periph/spi.h"
#include "periph_conf.h"
/* guard this file in case no SPI device is defined */
#if SPI_NUMOF
/* static port mapping */
static NRF_SPI_Type *const spi[] = {
#if SPI_0_EN
SPI_0_DEV,
#endif
#if SPI_1_EN
SPI_1_DEV
#endif
};
/**
* @brief array holding one pre-initialized mutex for each SPI device
*/
static mutex_t locks[] = {
#if SPI_0_EN
[SPI_0] = MUTEX_INIT,
#endif
#if SPI_1_EN
[SPI_1] = MUTEX_INIT,
#endif
};
int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
{
if (dev >= SPI_NUMOF) {
return -1;
}
spi_poweron(dev);
/* disable the device -> nRF51822 reference 3.0 26.1.1 and 27.1*/
spi[dev]->ENABLE = 0;
switch (dev) {
#if SPI_0_EN
case SPI_0:
/* disable TWI Interface */
NRF_TWI0->ENABLE = 0;
break;
#endif
#if SPI_1_EN
case SPI_1:
/* disable SPI Slave */
NRF_SPIS1->ENABLE = 0;
/* disable TWI Interface */
NRF_TWI1->ENABLE = 0;
break;
#endif
default:
return -1;
}
/* configure direction of used pins */
spi_conf_pins(dev);
/* configure SPI mode */
switch (conf) {
case SPI_CONF_FIRST_RISING:
spi[dev]->CONFIG = (SPI_CONFIG_CPOL_ActiveHigh << 2) | (SPI_CONFIG_CPHA_Leading << 1);
break;
case SPI_CONF_SECOND_RISING:
spi[dev]->CONFIG = (SPI_CONFIG_CPOL_ActiveHigh << 2) | (SPI_CONFIG_CPHA_Trailing << 1);
break;
case SPI_CONF_FIRST_FALLING:
spi[dev]->CONFIG = (SPI_CONFIG_CPOL_ActiveLow << 2) | (SPI_CONFIG_CPHA_Leading << 1);
break;
case SPI_CONF_SECOND_FALLING:
spi[dev]->CONFIG = (SPI_CONFIG_CPOL_ActiveLow << 2) | (SPI_CONFIG_CPHA_Trailing << 1);
break;
}
/* select bus speed */
switch (speed) {
case SPI_SPEED_100KHZ: /* 125 KHz for this device */
spi[dev]->FREQUENCY = SPI_FREQUENCY_FREQUENCY_K125;
break;
case SPI_SPEED_400KHZ: /* 500 KHz for this device */
spi[dev]->FREQUENCY = SPI_FREQUENCY_FREQUENCY_K500;
break;
case SPI_SPEED_1MHZ: /* 1 MHz for this device */
spi[dev]->FREQUENCY = SPI_FREQUENCY_FREQUENCY_M1;
break;
case SPI_SPEED_5MHZ: /* 4 MHz for this device */
spi[dev]->FREQUENCY = SPI_FREQUENCY_FREQUENCY_M4;
break;
case SPI_SPEED_10MHZ: /* 8 MHz for this device */
spi[dev]->FREQUENCY = SPI_FREQUENCY_FREQUENCY_M8;
break;
}
/* finally enable the device */
spi[dev]->ENABLE = 1;
return 0;
}
int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char data))
{
/* This API is incompatible with nRF51 SPIS */
return -1;
}
int spi_conf_pins(spi_t dev)
{
if (dev >= SPI_NUMOF) {
return -1;
}
switch (dev) {
#if SPI_0_EN
case SPI_0:
/* set pin direction */
NRF_P0->DIRSET = (1 << SPI_0_PIN_MOSI) | (1 << SPI_0_PIN_SCK);
NRF_P0->DIRCLR = (1 << SPI_0_PIN_MISO);
/* select pins to be used by SPI */
spi[dev]->PSELMOSI = SPI_0_PIN_MOSI;
spi[dev]->PSELMISO = SPI_0_PIN_MISO;
spi[dev]->PSELSCK = SPI_0_PIN_SCK;
break;
#endif
#if SPI_1_EN
case SPI_1:
/* set pin direction */
NRF_P0->DIRSET = (1 << SPI_1_PIN_MOSI) | (1 << SPI_1_PIN_SCK);
NRF_P0->DIRCLR = (1 << SPI_1_PIN_MISO);
/* select pins to be used by SPI */
spi[dev]->PSELMOSI = SPI_1_PIN_MOSI;
spi[dev]->PSELMISO = SPI_1_PIN_MISO;
spi[dev]->PSELSCK = SPI_1_PIN_SCK;
break;
#endif
}
return 0;
}
int spi_acquire(spi_t dev)
{
if (dev >= SPI_NUMOF) {
return -1;
}
mutex_lock(&locks[dev]);
return 0;
}
int spi_release(spi_t dev)
{
if (dev >= SPI_NUMOF) {
return -1;
}
mutex_unlock(&locks[dev]);
return 0;
}
int spi_transfer_byte(spi_t dev, char out, char *in)
{
return spi_transfer_bytes(dev, &out, in, 1);
}
int spi_transfer_bytes(spi_t dev, char *out, char *in, unsigned int length)
{
if (dev >= SPI_NUMOF) {
return -1;
}
for (int i = 0; i < length; i++) {
char tmp = (out) ? out[i] : 0;
spi[dev]->EVENTS_READY = 0;
spi[dev]->TXD = (uint8_t)tmp;
while (spi[dev]->EVENTS_READY != 1);
tmp = (char)spi[dev]->RXD;
if (in) {
in[i] = tmp;
}
}
return length;
}
int spi_transfer_reg(spi_t dev, uint8_t reg, char out, char *in)
{
spi_transfer_byte(dev, reg, 0);
return spi_transfer_byte(dev, out, in);
}
int spi_transfer_regs(spi_t dev, uint8_t reg, char *out, char *in, unsigned int length)
{
spi_transfer_byte(dev, reg, 0);
return spi_transfer_bytes(dev, out, in, length);
}
void spi_transmission_begin(spi_t dev, char reset_val)
{
/* spi slave is not implemented */
}
void spi_poweron(spi_t dev)
{
if (dev < SPI_NUMOF) {
spi[dev]->POWER = 1;
}
}
void spi_poweroff(spi_t dev)
{
if (dev < SPI_NUMOF) {
spi[dev]->POWER = 0;
}
}
#endif /* SPI_NUMOF */

358
cpu/nrf52/periph/timer.c Normal file
View File

@ -0,0 +1,358 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the peripheral timer interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include "cpu.h"
#include "board.h"
#include "sched.h"
#include "thread.h"
#include "periph_conf.h"
#include "periph/timer.h"
/**
* @name Flags to mark active channels
* @{
*/
#define TIMER_CH0 0x01
#define TIMER_CH1 0x02
#define TIMER_CH2 0x04
/** @} */
/**
* @brief struct for keeping track of a timer's state
*/
typedef struct {
void (*cb)(int);
uint8_t flags;
} timer_conf_t;
/**
* @brief timer state memory
*/
static timer_conf_t timer_config[TIMER_NUMOF];
/**
* @brief static timer mapping
*/
static NRF_TIMER_Type *const timer[] = {
#if TIMER_0_EN
TIMER_0_DEV,
#endif
#if TIMER_1_EN
TIMER_1_DEV,
#endif
#if TIMER_2_EN
TIMER_2_DEV
#endif
};
int timer_init(tim_t dev, unsigned int ticks_per_us, void (*callback)(int))
{
if (dev >= TIMER_NUMOF) {
return -1;
}
/* save callback */
timer_config[dev].cb = callback;
/* power on timer */
/* timer[dev]->POWER = 1; */
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
TIMER_0_DEV->BITMODE = TIMER_0_BITMODE;
NVIC_EnableIRQ(TIMER_0_IRQ);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
TIMER_1_DEV->BITMODE = TIEMR_1_BITMODE;
NVIC_EnableIRQ(TIMER_1_IRQ);
break;
#endif
#if TIMER_2_EN
case TIMER_2:
TIMER_2_DEV->BITMODE = TIMER_2_BITMODE;
NVIC_EnableIRQ(TIMER_2_IRQ);
break;
#endif
case TIMER_UNDEFINED:
return -1;
}
timer[dev]->TASKS_STOP = 1;
timer[dev]->MODE = TIMER_MODE_MODE_Timer; /* set the timer in Timer Mode. */
timer[dev]->TASKS_CLEAR = 1; /* clear the task first to be usable for later. */
switch (ticks_per_us) {
case 1:
timer[dev]->PRESCALER = 4;
break;
case 2:
timer[dev]->PRESCALER = 5;
break;
case 4:
timer[dev]->PRESCALER = 6;
break;
case 8:
timer[dev]->PRESCALER = 7;
break;
case 16:
timer[dev]->PRESCALER = 8;
break;
default:
return -1;
}
/* reset compare state */
timer[dev]->EVENTS_COMPARE[0] = 0;
timer[dev]->EVENTS_COMPARE[1] = 0;
timer[dev]->EVENTS_COMPARE[2] = 0;
/* start the timer */
timer[dev]->TASKS_START = 1;
return 0;
}
int timer_set(tim_t dev, int channel, unsigned int timeout)
{
uint32_t now = timer_read(dev);
return timer_set_absolute(dev, channel, (now + timeout - 1));
}
int timer_set_absolute(tim_t dev, int channel, unsigned int value)
{
if (dev >= TIMER_NUMOF) {
return -1;
}
switch (channel) {
case 0:
timer[dev]->CC[0] = value;
timer_config[dev].flags |= TIMER_CH0;
timer[dev]->INTENSET |= TIMER_INTENSET_COMPARE0_Msk;
break;
case 1:
timer[dev]->CC[1] = value;
timer_config[dev].flags |= TIMER_CH1;
timer[dev]->INTENSET |= TIMER_INTENSET_COMPARE1_Msk;
break;
case 2:
timer[dev]->CC[2] = value;
timer_config[dev].flags |= TIMER_CH2;
timer[dev]->INTENSET |= TIMER_INTENSET_COMPARE2_Msk;
break;
default:
return -2;
}
return 1;
}
int timer_clear(tim_t dev, int channel)
{
if (dev >= TIMER_NUMOF) {
return -1;
}
/* set timeout value */
switch (channel) {
case 0:
timer_config[dev].flags &= ~TIMER_CH0;
timer[dev]->INTENCLR = TIMER_INTENCLR_COMPARE0_Msk;
break;
case 1:
timer_config[dev].flags &= ~TIMER_CH1;
timer[dev]->INTENCLR = TIMER_INTENCLR_COMPARE1_Msk;
break;
case 2:
timer_config[dev].flags &= ~TIMER_CH2;
timer[dev]->INTENCLR = TIMER_INTENCLR_COMPARE2_Msk;
break;
default:
return -2;
}
return 1;
}
unsigned int timer_read(tim_t dev)
{
if (dev >= TIMER_NUMOF) {
return 0;
}
timer[dev]->TASKS_CAPTURE[3] = 1;
return timer[dev]->CC[3];
}
void timer_start(tim_t dev)
{
if (dev < TIMER_NUMOF) {
timer[dev]->TASKS_START = 1;
}
}
void timer_stop(tim_t dev)
{
if (dev < TIMER_NUMOF) {
timer[dev]->TASKS_STOP = 1;
}
}
void timer_irq_enable(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
NVIC_EnableIRQ(TIMER_0_IRQ);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
NVIC_EnableIRQ(TIMER_1_IRQ);
break;
#endif
#if TIMER_2_EN
case TIMER_2:
NVIC_EnableIRQ(TIMER_2_IRQ);
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_irq_disable(tim_t dev)
{
switch (dev) {
#if TIMER_0_EN
case TIMER_0:
NVIC_DisableIRQ(TIMER_0_IRQ);
break;
#endif
#if TIMER_1_EN
case TIMER_1:
NVIC_DisableIRQ(TIMER_1_IRQ);
break;
#endif
#if TIMER_2_EN
case TIMER_2:
NVIC_DisableIRQ(TIMER_2_IRQ);
break;
#endif
case TIMER_UNDEFINED:
break;
}
}
void timer_reset(tim_t dev)
{
if (dev < TIMER_NUMOF) {
timer[dev]->TASKS_CLEAR = 1;
}
}
#if TIMER_0_EN
void TIMER_0_ISR(void)
{
for (int i = 0; i < TIMER_0_CHANNELS; i++) {
if (TIMER_0_DEV->EVENTS_COMPARE[i] == 1) {
TIMER_0_DEV->EVENTS_COMPARE[i] = 0;
if (timer_config[TIMER_0].flags & (1 << i)) {
timer_config[TIMER_0].flags &= ~(1 << i);
TIMER_0_DEV->INTENCLR = (1 << (16 + i));
timer_config[TIMER_0].cb(i);
}
}
}
if (sched_context_switch_request) {
thread_yield();
}
}
#endif
#if TIMER_1_EN
void TIMER_1_ISR(void)
{
for (int i = 0; i < TIMER_1_CHANNELS; i++) {
if (TIMER_1_DEV->EVENTS_COMPARE[i] == 1) {
TIMER_1_DEV->EVENTS_COMPARE[i] = 0;
if (timer_config[TIMER_1].flags & (1 << i)) {
timer_config[TIMER_1].flags &= ~(1 << i);
TIMER_1_DEV->INTENCLR = (1 << (16 + i));
timer_config[TIMER_1].cb(i);
}
}
}
if (sched_context_switch_request) {
thread_yield();
}
}
#endif
#if TIMER_2_EN
void TIMER_2_ISR(void)
{
for (int i = 0; i < TIMER_2_CHANNELS; i++) {
if (TIMER_2_DEV->EVENTS_COMPARE[i] == 1) {
TIMER_2_DEV->EVENTS_COMPARE[i] = 0;
if (timer_config[TIMER_2].flags & (1 << i)) {
timer_config[TIMER_2].flags &= ~(1 << i);
TIMER_2_DEV->INTENCLR = (1 << (16 + i));
timer_config[TIMER_2].cb(i);
}
}
}
if (sched_context_switch_request) {
thread_yield();
}
}
#endif

169
cpu/nrf52/periph/uart.c Normal file
View File

@ -0,0 +1,169 @@
/*
* Copyright (C) 2015 Jan Wagner <mail@jwagner.eu>
* 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief Implementation of the peripheral UART interface
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Jan Wagner <mail@jwagner.eu>
*
* @}
*/
#include <stdint.h>
#include "cpu.h"
#include "thread.h"
#include "sched.h"
#include "periph_conf.h"
#include "periph/uart.h"
#include "board.h"
/**
* @brief Allocate memory to store the callback functions.
*/
static uart_isr_ctx_t uart_config;
int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
{
if (uart != 0) {
return -1;
}
/* remember callback addresses and argument */
uart_config.rx_cb = rx_cb;
uart_config.arg = arg;
/* reset configuration registers */
NRF_UART0->CONFIG = 0;
/* configure RX/TX pin modes */
NRF_P0->DIRSET = (1 << UART_PIN_TX);
NRF_P0->DIRCLR = (1 << UART_PIN_RX);
/* configure UART pins to use */
NRF_UART0->PSELTXD = UART_PIN_TX;
NRF_UART0->PSELRXD = UART_PIN_RX;
/* enable HW-flow control if defined */
#if UART_HWFLOWCTRL
/* set pin mode for RTS and CTS pins */
NRF_P0->DIRSET = (1 << UART_PIN_RTS);
NRF_P0->DIRCLR = (1 << UART_PIN_CTS);
/* configure RTS and CTS pins to use */
NRF_UART0->PSELRTS = UART_PIN_RTS;
NRF_UART0->PSELCTS = UART_PIN_CTS;
NRF_UART0->CONFIG |= UART_CONFIG_HWFC_Msk; /* enable HW flow control */
#else
NRF_UART0->PSELRTS = 0xffffffff; /* pin disconnected */
NRF_UART0->PSELCTS = 0xffffffff; /* pin disconnected */
#endif
/* select baudrate */
switch (baudrate) {
case 1200:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud1200;
break;
case 2400:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud2400;
break;
case 4800:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud4800;
break;
case 9600:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud9600;
break;
case 14400:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud14400;
break;
case 19200:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud19200;
break;
case 28800:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud28800;
break;
case 38400:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud38400;
break;
case 57600:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud57600;
break;
case 76800:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud76800;
break;
case 115200:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud115200;
break;
case 230400:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud230400;
break;
case 250000:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud250000;
break;
case 460800:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud460800;
break;
case 921600:
NRF_UART0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud921600;
break;
default:
return -2;
}
/* enable the UART device */
NRF_UART0->ENABLE = UART_ENABLE_ENABLE_Enabled;
/* enable TX and RX */
NRF_UART0->TASKS_STARTTX = 1;
NRF_UART0->TASKS_STARTRX = 1;
/* enable global and receiving interrupt */
NVIC_EnableIRQ(UARTE0_UART0_IRQn);
NRF_UART0->INTENSET = UART_INTENSET_RXDRDY_Msk;
return 0;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len)
{
if (uart == 0) {
for (size_t i = 0; i < len; i++) {
/* write data into transmit register */
NRF_UART0->TXD = data[i];
/* wait for any transmission to be done */
while (NRF_UART0->EVENTS_TXDRDY == 0);
/* reset ready flag */
NRF_UART0->EVENTS_TXDRDY = 0;
}
}
}
void uart_poweron(uart_t uart)
{
(void)uart;
NRF_UART0->TASKS_STARTRX = 1;
NRF_UART0->TASKS_STARTTX = 1;
}
void uart_poweroff(uart_t uart)
{
(void)uart;
NRF_UART0->TASKS_SUSPEND;
}
void isr_uart0(void)
{
if (NRF_UART0->EVENTS_RXDRDY == 1) {
NRF_UART0->EVENTS_RXDRDY = 0;
char byte = (char)(NRF_UART0->RXD & 0xff);
uart_config.rx_cb(uart_config.arg, byte);
}
if (sched_context_switch_request) {
thread_yield();
}
}

140
cpu/nrf52/vectors.c Normal file
View File

@ -0,0 +1,140 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* 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_nrf52
* @{
*
* @file
* @brief nRF52 interrupt vector definitions
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include <stdint.h>
#include "cpu.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);
/* nRF52 specific interrupt vectors */
WEAK_DEFAULT void isr_power_clock(void);
WEAK_DEFAULT void isr_radio(void);
WEAK_DEFAULT void isr_uart0(void);
WEAK_DEFAULT void isr_spi0_twi0(void);
WEAK_DEFAULT void isr_spi1_twi1(void);
WEAK_DEFAULT void isr_nfct(void);
WEAK_DEFAULT void isr_gpiote(void);
WEAK_DEFAULT void isr_saadc(void);
WEAK_DEFAULT void isr_timer0(void);
WEAK_DEFAULT void isr_timer1(void);
WEAK_DEFAULT void isr_timer2(void);
WEAK_DEFAULT void isr_rtc0(void);
WEAK_DEFAULT void isr_temp(void);
WEAK_DEFAULT void isr_rng(void);
WEAK_DEFAULT void isr_ecb(void);
WEAK_DEFAULT void isr_ccm_aar(void);
WEAK_DEFAULT void isr_wdt(void);
WEAK_DEFAULT void isr_rtc1(void);
WEAK_DEFAULT void isr_qdec(void);
WEAK_DEFAULT void isr_lpcomp(void);
WEAK_DEFAULT void isr_swi0(void);
WEAK_DEFAULT void isr_swi1(void);
WEAK_DEFAULT void isr_swi2(void);
WEAK_DEFAULT void isr_swi3(void);
WEAK_DEFAULT void isr_swi4(void);
WEAK_DEFAULT void isr_swi5(void);
WEAK_DEFAULT void isr_timer3(void);
WEAK_DEFAULT void isr_timer4(void);
WEAK_DEFAULT void isr_pwm0(void);
WEAK_DEFAULT void isr_pdm(void);
WEAK_DEFAULT void isr_mwu(void);
WEAK_DEFAULT void isr_pwm1(void);
WEAK_DEFAULT void isr_pwm2(void);
WEAK_DEFAULT void isr_spi2(void);
WEAK_DEFAULT void isr_rtc2(void);
WEAK_DEFAULT void isr_i2s(void);
/* interrupt vector table */
ISR_VECTORS const void *interrupt_vector[] = {
/* Exception stack pointer */
(void*) (&_estack), /* pointer to the top of the stack */
/* Cortex-M4 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 */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) (0UL), /* Reserved */
(void*) isr_svc, /* system call interrupt, in RIOT used for
* switching into thread context on boot */
(void*) debug_mon_default, /* debug monitor exception */
(void*) (0UL), /* Reserved */
(void*) isr_pendsv, /* pendSV interrupt, in RIOT the actual
* context switching is happening here */
(void*) isr_systick, /* SysTick interrupt, not used in RIOT */
/* nRF52 specific peripheral handlers */
(void *) isr_power_clock, /* power_clock */
(void *) isr_radio, /* radio */
(void *) isr_uart0, /* uart0 */
(void *) isr_spi0_twi0, /* spi0_twi0 */
(void *) isr_spi1_twi1, /* spi1_twi1 */
(void *) isr_nfct, /* nfct */
(void *) isr_gpiote, /* gpiote */
(void *) isr_saadc, /* adc */
(void *) isr_timer0, /* timer0 */
(void *) isr_timer1, /* timer1 */
(void *) isr_timer2, /* timer2 */
(void *) isr_rtc0, /* rtc0 */
(void *) isr_temp, /* temp */
(void *) isr_rng, /* rng */
(void *) isr_ecb, /* ecb */
(void *) isr_ccm_aar, /* ccm_aar */
(void *) isr_wdt, /* wdt */
(void *) isr_rtc1, /* rtc1 */
(void *) isr_qdec, /* qdec */
(void *) isr_lpcomp, /* lpcomp */
(void *) isr_swi0, /* swi0 */
(void *) isr_swi1, /* swi1 */
(void *) isr_swi2, /* swi2 */
(void *) isr_swi3, /* swi3 */
(void *) isr_swi4, /* swi4 */
(void *) isr_swi5, /* swi5 */
(void *) isr_timer3, /* timer 3 */
(void *) isr_timer4, /* timer 4 */
(void *) isr_pwm0, /* pwm 0 */
(void *) isr_pdm, /* pdm */
(void *)(0UL), /* reserved */
(void *)(0UL), /* reserved */
(void *) isr_mwu, /* mwu */
(void *) isr_pwm1, /* pwm 1 */
(void *) isr_pwm2, /* pwm 2 */
(void *) isr_spi2, /* spi 2 */
(void *) isr_rtc2, /* rtc 2 */
(void *) isr_i2s, /* i2s */
};

View File

@ -829,7 +829,7 @@ EXCLUDE_PATTERNS = */board/*/tools/* \
*/cpu/cortexm_common/include/core_cm*.h \
*/cpu/stm32f*/include/stm32f* \
*/drivers/nrf24l01p/include/nrf24l01p_settings.h \
*/cpu/nrf51/include/nrf51*.h \
*/cpu/nrf5*/include/nrf5*.h \
*/cpu/lpc1768/include/LPC17xx.h \
*/cpu/lpc11u34/include/LPC11Uxx.h \
*/boards/*/include/periph_conf.h \