cpu/nrf52: added support for nRF52840

- added vendor header files for nrf52840
- added config for nrf52840
- added additional isr vectors for the nrf52840
- enabled port 1 in GPIO driver
- adapted periph drivers to cope with GPIO driver changes
- adapted the GPIO config of the I2C driver for the nrf51
This commit is contained in:
Hauke Petersen 2017-04-05 12:10:13 +02:00
parent bca6190e3c
commit 334b2a6dc1
16 changed files with 17249 additions and 36 deletions

View File

@ -1,6 +1,6 @@
# define the cpu used by the nRF52 DK # define the cpu used by the nRF52 DK
export CPU = nrf52 export CPU = nrf52
export CPU_MODEL = nrf52xxaa export CPU_MODEL = nrf52832xxaa
# set default port depending on operating system # set default port depending on operating system
PORT_LINUX ?= /dev/ttyACM0 PORT_LINUX ?= /dev/ttyACM0

View File

@ -29,7 +29,6 @@ extern "C" {
* @brief Redefine some peripheral names to unify them between nRF51 and 52 * @brief Redefine some peripheral names to unify them between nRF51 and 52
* @{ * @{
*/ */
#define GPIO_BASE (NRF_GPIO)
#define UART_IRQN (UART0_IRQn) #define UART_IRQN (UART0_IRQn)
#define SPI_SCKSEL (dev(bus)->PSELSCK) #define SPI_SCKSEL (dev(bus)->PSELSCK)
#define SPI_MOSISEL (dev(bus)->PSELMOSI) #define SPI_MOSISEL (dev(bus)->PSELMOSI)

View File

@ -101,8 +101,8 @@ int i2c_init_master(i2c_t bus, i2c_speed_t speed)
dev(bus)->POWER = TWI_POWER_POWER_Enabled; dev(bus)->POWER = TWI_POWER_POWER_Enabled;
/* pin configuration */ /* pin configuration */
GPIO_BASE->PIN_CNF[i2c_config[bus].pin_scl] = (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos); NRF_GPIO->PIN_CNF[i2c_config[bus].pin_scl] = (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos);
GPIO_BASE->PIN_CNF[i2c_config[bus].pin_scl] = (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos); NRF_GPIO->PIN_CNF[i2c_config[bus].pin_scl] = (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos);
dev(bus)->PSELSCL = i2c_config[bus].pin_scl; dev(bus)->PSELSCL = i2c_config[bus].pin_scl;
dev(bus)->PSELSDA = i2c_config[bus].pin_sda; dev(bus)->PSELSDA = i2c_config[bus].pin_sda;

View File

@ -21,20 +21,32 @@
#define CPU_CONF_H #define CPU_CONF_H
#include "cpu_conf_common.h" #include "cpu_conf_common.h"
#ifdef CPU_MODEL_NRF52832XXAA
#include "vendor/nrf52.h" #include "vendor/nrf52.h"
#include "vendor/nrf52_bitfields.h" #include "vendor/nrf52_bitfields.h"
#elif defined(CPU_MODEL_NRF52840XXAA)
#include "vendor/nrf52840.h"
#include "vendor/nrf52840_bitfields.h"
#else
#error "The CPU_MODEL of your board is currently not supported"
#endif
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
/** /**
* @brief ARM Cortex-M specific CPU configuration * @name ARM Cortex-M specific CPU configuration
* @{ * @{
*/ */
#define CPU_DEFAULT_IRQ_PRIO (2U) #define CPU_DEFAULT_IRQ_PRIO (2U)
#define CPU_IRQ_NUMOF (38U)
#define CPU_FLASH_BASE (0x00000000) #define CPU_FLASH_BASE (0x00000000)
#ifdef CPU_MODEL_NRF52832XXAA
#define CPU_IRQ_NUMOF (38U)
#elif CPU_MODEL_NRF52840XXAA
#define CPU_IRQ_NUMOF (46U)
#endif
/** @} */ /** @} */
/** /**
@ -43,8 +55,10 @@ extern "C" {
*/ */
#define FLASHPAGE_SIZE (4096U) #define FLASHPAGE_SIZE (4096U)
#if defined(CPU_MODEL_NRF52XXAA) #if defined(CPU_MODEL_NRF52832XXAA)
#define FLASHPAGE_NUMOF (128U) #define FLASHPAGE_NUMOF (128U)
#elif defined(CPU_MODEL_NRF52840XXAA)
#define FLASHPAGE_NUMOF (256U)
#endif #endif
/** @} */ /** @} */

View File

@ -29,7 +29,6 @@ extern "C" {
* @brief Redefine some peripheral names to unify them between nRF51 and 52 * @brief Redefine some peripheral names to unify them between nRF51 and 52
* @{ * @{
*/ */
#define GPIO_BASE (NRF_P0)
#define UART_IRQN (UARTE0_UART0_IRQn) #define UART_IRQN (UARTE0_UART0_IRQn)
#define SPI_SCKSEL (dev(bus)->PSEL.SCK) #define SPI_SCKSEL (dev(bus)->PSEL.SCK)
#define SPI_MOSISEL (dev(bus)->PSEL.MOSI) #define SPI_MOSISEL (dev(bus)->PSEL.MOSI)

2426
cpu/nrf52/include/vendor/nrf52840.h vendored 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,27 @@
/*
* Copyright (C) 2017 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 NRF52840XXAA
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x00000000, LENGTH = 1024K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 256K
}
INCLUDE cortexm_base.ld

View File

@ -0,0 +1,27 @@
/*
* Copyright (C) 2017 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 NRF52840XXAA
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
MEMORY
{
rom (rx) : ORIGIN = 0x1f000, LENGTH = 0xe1000
ram (rwx) : ORIGIN = 0x20002800, LENGTH = 0x3D800
}
INCLUDE cortexm_base.ld

View File

@ -89,6 +89,15 @@ WEAK_DEFAULT void isr_spi2(void);
WEAK_DEFAULT void isr_rtc2(void); WEAK_DEFAULT void isr_rtc2(void);
WEAK_DEFAULT void isr_i2s(void); WEAK_DEFAULT void isr_i2s(void);
#ifdef CPU_MODEL_NRF52840XXAA
WEAK_DEFAULT void isr_fpu(void);
WEAK_DEFAULT void isr_usbd(void);
WEAK_DEFAULT void isr_uarte1(void);
WEAK_DEFAULT void isr_qspi(void);
WEAK_DEFAULT void isr_cryptocell(void);
WEAK_DEFAULT void isr_spi3(void);
WEAK_DEFAULT void isr_pwm3(void);
#endif
#ifdef SOFTDEVICE_PRESENT #ifdef SOFTDEVICE_PRESENT
extern void SWI2_EGU2_IRQHandler(void); extern void SWI2_EGU2_IRQHandler(void);
@ -144,9 +153,9 @@ ISR_VECTORS const void *interrupt_vector[] = {
#else #else
(void *) isr_swi2, /* swi2 */ (void *) isr_swi2, /* swi2 */
#endif #endif
(void *) (0UL), /* swi3 */ (void *) isr_swi3, /* swi3 */
(void *) (0UL), /* swi4 */ (void *) isr_swi4, /* swi4 */
(void *) (0UL), /* swi5 */ (void *) isr_swi5, /* swi5 */
(void *) isr_timer3, /* timer 3 */ (void *) isr_timer3, /* timer 3 */
(void *) isr_timer4, /* timer 4 */ (void *) isr_timer4, /* timer 4 */
(void *) isr_pwm0, /* pwm 0 */ (void *) isr_pwm0, /* pwm 0 */
@ -159,4 +168,14 @@ ISR_VECTORS const void *interrupt_vector[] = {
(void *) isr_spi2, /* spi 2 */ (void *) isr_spi2, /* spi 2 */
(void *) isr_rtc2, /* rtc 2 */ (void *) isr_rtc2, /* rtc 2 */
(void *) isr_i2s, /* i2s */ (void *) isr_i2s, /* i2s */
#ifdef CPU_MODEL_NRF52840XXAA
(void *) isr_fpu, /* fpu */
(void *) isr_usbd, /* usbc */
(void *) isr_uarte1, /* uarte1 */
(void *) isr_qspi, /* qspi */
(void *) isr_cryptocell, /* cryptocell */
(void *) isr_spi3, /* spi3 */
(void *) (0UL), /* reserved */
(void *) isr_pwm3, /* pwm3 */
#endif
}; };

View File

@ -35,11 +35,15 @@ extern "C" {
#define CPUID_LEN (8U) #define CPUID_LEN (8U)
/** /**
* @brief Override macro for defining GPIO pins * @name Override macro for defining GPIO pins
* *
* The port definition is used (and zeroed) to suppress compiler warnings * The port definition is used (and zeroed) to suppress compiler warnings
*/ */
#ifdef CPU_MODEL_NRF52840XXAA
#define GPIO_PIN(x,y) ((x << 5) | y)
#else
#define GPIO_PIN(x,y) ((x & 0) | y) #define GPIO_PIN(x,y) ((x & 0) | y)
#endif
/** /**
* @brief Generate GPIO mode bitfields * @brief Generate GPIO mode bitfields

View File

@ -30,11 +30,39 @@
#include "periph_cpu.h" #include "periph_cpu.h"
#include "periph_conf.h" #include "periph_conf.h"
#define PORT_BIT (1 << 5)
#define PIN_MASK (0x1f)
/** /**
* @brief Place to store the interrupt context * @brief Place to store the interrupt context
*/ */
static gpio_isr_ctx_t exti_chan; static gpio_isr_ctx_t exti_chan;
/**
* @brief Get the port's base address
*/
static inline NRF_GPIO_Type* port(gpio_t pin)
{
#if (CPU_FAM_NRF51)
return NRF_GPIO;
#elif defined(CPU_MODEL_NRF52832XXAA)
return NRF_P0;
#else
return (pin & PORT_BIT) ? NRF_P1 : NRF_P0;
#endif
}
/**
* @brief Get a pin's offset
*/
static inline int pin_num(gpio_t pin)
{
#ifdef CPU_MODEL_NRF52840XXAA
return (pin & PIN_MASK);
#else
return (int)pin;
#endif
}
int gpio_init(gpio_t pin, gpio_mode_t mode) int gpio_init(gpio_t pin, gpio_mode_t mode)
{ {
@ -44,7 +72,7 @@ int gpio_init(gpio_t pin, gpio_mode_t mode)
case GPIO_IN_PU: case GPIO_IN_PU:
case GPIO_OUT: case GPIO_OUT:
/* configure pin direction, input buffer and pull resistor state */ /* configure pin direction, input buffer and pull resistor state */
GPIO_BASE->PIN_CNF[pin] = mode; port(pin)->PIN_CNF[pin] = mode;
break; break;
default: default:
return -1; return -1;
@ -68,6 +96,9 @@ int gpio_init_int(gpio_t pin, gpio_mode_t mode, gpio_flank_t flank,
/* configure the GPIOTE channel: set even mode, pin and active flank */ /* configure the GPIOTE channel: set even mode, pin and active flank */
NRF_GPIOTE->CONFIG[0] = (GPIOTE_CONFIG_MODE_Event | NRF_GPIOTE->CONFIG[0] = (GPIOTE_CONFIG_MODE_Event |
(pin << GPIOTE_CONFIG_PSEL_Pos) | (pin << GPIOTE_CONFIG_PSEL_Pos) |
#ifdef CPU_MODEL_NRF52840XXAA
((pin & PORT_BIT) << 8) |
#endif
(flank << GPIOTE_CONFIG_POLARITY_Pos)); (flank << GPIOTE_CONFIG_POLARITY_Pos));
/* enable external interrupt */ /* enable external interrupt */
NRF_GPIOTE->INTENSET |= GPIOTE_INTENSET_IN0_Msk; NRF_GPIOTE->INTENSET |= GPIOTE_INTENSET_IN0_Msk;
@ -88,35 +119,35 @@ void gpio_irq_disable(gpio_t pin)
int gpio_read(gpio_t pin) int gpio_read(gpio_t pin)
{ {
if (GPIO_BASE->DIR & (1 << pin)) { if (port(pin)->DIR & (1 << pin)) {
return (GPIO_BASE->OUT & (1 << pin)) ? 1 : 0; return (port(pin)->OUT & (1 << pin)) ? 1 : 0;
} }
else { else {
return (GPIO_BASE->IN & (1 << pin)) ? 1 : 0; return (port(pin)->IN & (1 << pin)) ? 1 : 0;
} }
} }
void gpio_set(gpio_t pin) void gpio_set(gpio_t pin)
{ {
GPIO_BASE->OUTSET = (1 << pin); port(pin)->OUTSET = (1 << pin);
} }
void gpio_clear(gpio_t pin) void gpio_clear(gpio_t pin)
{ {
GPIO_BASE->OUTCLR = (1 << pin); port(pin)->OUTCLR = (1 << pin);
} }
void gpio_toggle(gpio_t pin) void gpio_toggle(gpio_t pin)
{ {
GPIO_BASE->OUT ^= (1 << pin); port(pin)->OUT ^= (1 << pin);
} }
void gpio_write(gpio_t pin, int value) void gpio_write(gpio_t pin, int value)
{ {
if (value) { if (value) {
GPIO_BASE->OUTSET = (1 << pin); port(pin)->OUTSET = (1 << pin);
} else { } else {
GPIO_BASE->OUTCLR = (1 << pin); port(pin)->OUTCLR = (1 << pin);
} }
} }

View File

@ -24,6 +24,7 @@
#include "mutex.h" #include "mutex.h"
#include "assert.h" #include "assert.h"
#include "periph/spi.h" #include "periph/spi.h"
#include "periph/gpio.h"
#ifdef SPI_NUMOF #ifdef SPI_NUMOF
@ -50,9 +51,9 @@ void spi_init(spi_t bus)
void spi_init_pins(spi_t bus) void spi_init_pins(spi_t bus)
{ {
/* set pin direction */ /* set pin direction */
GPIO_BASE->DIRSET = ((1 << spi_config[bus].sclk) | gpio_init(spi_config[bus].sclk, GPIO_OUT);
(1 << spi_config[bus].mosi)); gpio_init(spi_config[bus].mosi, GPIO_OUT);
GPIO_BASE->DIRCLR = (1 << spi_config[bus].miso); gpio_init(spi_config[bus].miso, GPIO_IN);
/* select pins for the SPI device */ /* select pins for the SPI device */
SPI_SCKSEL = spi_config[bus].sclk; SPI_SCKSEL = spi_config[bus].sclk;
SPI_MOSISEL = spi_config[bus].mosi; SPI_MOSISEL = spi_config[bus].mosi;

View File

@ -27,9 +27,19 @@
#include "cpu.h" #include "cpu.h"
#include "periph/uart.h" #include "periph/uart.h"
#include "periph_cpu.h" #include "periph/gpio.h"
#include "periph_conf.h"
#ifdef CPU_MODEL_NRF52840XXAA
#define PSEL_RXD NRF_UART0->PSEL.RXD
#define PSEL_TXD NRF_UART0->PSEL.TXD
#define PSEL_RTS NRF_UART0->PSEL.RTS
#define PSEL_CTS NRF_UART0->PSEL.CTS
#else
#define PSEL_RXD NRF_UART0->PSELRXD
#define PSEL_TXD NRF_UART0->PSELTXD
#define PSEL_RTS NRF_UART0->PSELRTS
#define PSEL_CTS NRF_UART0->PSELCTS
#endif
/** /**
* @brief Allocate memory for the interrupt context * @brief Allocate memory for the interrupt context
@ -56,26 +66,26 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg)
/* configure RX pin */ /* configure RX pin */
if (rx_cb) { if (rx_cb) {
GPIO_BASE->DIRCLR = (1 << UART_PIN_RX); gpio_init(UART_PIN_RX, GPIO_IN);
NRF_UART0->PSELRXD = UART_PIN_RX; PSEL_RXD = UART_PIN_RX;
} }
/* configure TX pin */ /* configure TX pin */
GPIO_BASE->DIRSET = (1 << UART_PIN_TX); gpio_init(UART_PIN_TX, GPIO_OUT);
NRF_UART0->PSELTXD = UART_PIN_TX; PSEL_TXD = UART_PIN_TX;
/* enable HW-flow control if defined */ /* enable HW-flow control if defined */
#if UART_HWFLOWCTRL #if UART_HWFLOWCTRL
/* set pin mode for RTS and CTS pins */ /* set pin mode for RTS and CTS pins */
GPIO_BASE->DIRSET = (1 << UART_PIN_RTS); gpio_init(UART_PIN_RTS, GPIO_OUT);
GPIO_BASE->DIRCLR = (1 << UART_PIN_CTS); gpio_init(UART_PIN_CTS, GPIO_IN);
/* configure RTS and CTS pins to use */ /* configure RTS and CTS pins to use */
NRF_UART0->PSELRTS = UART_PIN_RTS; PSEL_RTS = UART_PIN_RTS;
NRF_UART0->PSELCTS = UART_PIN_CTS; PSEL_CTS = UART_PIN_CTS;
NRF_UART0->CONFIG |= UART_CONFIG_HWFC_Msk; /* enable HW flow control */ NRF_UART0->CONFIG |= UART_CONFIG_HWFC_Msk; /* enable HW flow control */
#else #else
NRF_UART0->PSELRTS = 0xffffffff; /* pin disconnected */ PSEL_RTS = 0xffffffff; /* pin disconnected */
NRF_UART0->PSELCTS = 0xffffffff; /* pin disconnected */ PSEL_CTS = 0xffffffff; /* pin disconnected */
#endif #endif
/* select baudrate */ /* select baudrate */