diff --git a/cpu/nrf51/Makefile b/cpu/nrf51/Makefile index 0dcb89e234..e4e81ca5d6 100644 --- a/cpu/nrf51/Makefile +++ b/cpu/nrf51/Makefile @@ -2,7 +2,7 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(RIOTCPU)/cortexm_common +DIRS = periph $(RIOTCPU)/cortexm_common $(RIOTCPU)/nrf5x_common # build one of the radio drivers, if enabled ifneq (,$(filter radio_nrfmin,$(USEMODULE))) diff --git a/cpu/nrf51/Makefile.include b/cpu/nrf51/Makefile.include index 04c2fd5dd4..a3b630b9b5 100644 --- a/cpu/nrf51/Makefile.include +++ b/cpu/nrf51/Makefile.include @@ -1,3 +1,5 @@ export CPU_ARCH = cortex-m0 +export CPU_FAM = nrf51 +include $(RIOTCPU)/nrf5x_common/Makefile.include include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/nrf51/include/periph_cpu.h b/cpu/nrf51/include/periph_cpu.h deleted file mode 100644 index 21d2e60205..0000000000 --- a/cpu/nrf51/include/periph_cpu.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright (C) 2015 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_nrf51822 - * @{ - * - * @file - * @brief CPU specific definitions for handling peripherals - * - * @author Hauke Petersen - */ - -#ifndef CPU_PERIPH_H_ -#define CPU_PERIPH_H_ - -#include "periph/dev_enums.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * @brief Mandatory macro for defining GPIO pins - * - * The port definition is used (and zeroed) to suppress compiler warnings - */ -#define GPIO_PIN(x,y) ((x & 0) | y) - -/** - * @brief Length of the CPU_ID in octets - */ -#define CPUID_LEN (8U) - -/** - * @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 = 2, /**< 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; -/** @} */ - -#ifdef __cplusplus -} -#endif - -#endif /* CPU_PERIPH_H_ */ -/** @} */ diff --git a/cpu/nrf51/periph/cpuid.c b/cpu/nrf51/periph/cpuid.c deleted file mode 100644 index a65227c526..0000000000 --- a/cpu/nrf51/periph/cpuid.c +++ /dev/null @@ -1,32 +0,0 @@ -/* - * Copyright (C) 2014-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_nrf51 - * @{ - * - * @file - * @brief CPU-ID driver implementation - * - * The NRF51822 provides a 64-bit unique identifier, that is unique for each - * shipped unit. - * - * @author Hauke Petersen - * - * @} - */ - -#include - -#include "cpu.h" -#include "periph/cpuid.h" - -void cpuid_get(void *id) -{ - memcpy(id, (void*)NRF_FICR->DEVICEID, CPUID_LEN); -} diff --git a/cpu/nrf51/periph/gpio.c b/cpu/nrf51/periph/gpio.c deleted file mode 100644 index 3f073e90d2..0000000000 --- a/cpu/nrf51/periph/gpio.c +++ /dev/null @@ -1,127 +0,0 @@ -/* - * Copyright (C) 2015 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_nrf51822 - * @{ - * - * @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 Christian Kühling - * @author Timo Ziegler - * @author Hauke Petersen - * - * @} - */ - -#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_GPIO->PIN_CNF[pin] = ((dir << GPIO_PIN_CNF_DIR_Pos) | - (dir << GPIO_PIN_CNF_INPUT_Pos) | - (pullup << GPIO_PIN_CNF_PULL_Pos)); - 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; -} - -/* - * the gpio_init_mux function is not defined as it is not needed for this CPU - */ - -void gpio_irq_enable(gpio_t pin) -{ - (void) pin; - NRF_GPIOTE->INTENSET |= GPIOTE_INTENSET_IN0_Msk; -} - -void gpio_irq_disable(gpio_t dev) -{ - (void) dev; - NRF_GPIOTE->INTENCLR |= GPIOTE_INTENSET_IN0_Msk; -} - -int gpio_read(gpio_t pin) -{ - if (NRF_GPIO->DIR & (1 << pin)) { - return (NRF_GPIO->OUT & (1 << pin)) ? 1 : 0; - } - else { - return (NRF_GPIO->IN & (1 << pin)) ? 1 : 0; - } -} - -void gpio_set(gpio_t pin) -{ - NRF_GPIO->OUTSET = (1 << pin); -} - -void gpio_clear(gpio_t pin) -{ - NRF_GPIO->OUTCLR = (1 << pin); -} - -void gpio_toggle(gpio_t pin) -{ - NRF_GPIO->OUT ^= (1 << pin); -} - -void gpio_write(gpio_t pin, int value) -{ - if (value) { - NRF_GPIO->OUTSET = (1 << pin); - } else { - NRF_GPIO->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(); - } -} diff --git a/cpu/nrf51/periph/uart.c b/cpu/nrf51/periph/uart.c deleted file mode 100644 index f5f8432bee..0000000000 --- a/cpu/nrf51/periph/uart.c +++ /dev/null @@ -1,172 +0,0 @@ -/* - * Copyright (C) 2014-2015 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_nrf51822 - * @{ - * - * @file - * @brief Low-level UART driver implementation - * - * @author Christian Kühling - * @author Timo Ziegler - * @author Hauke Petersen - * - * @} - */ - -#include - -#include "cpu.h" -#include "thread.h" -#include "sched.h" -#include "periph/uart.h" - -/** - * @brief Data structure holding the callbacks and argument for each UART device - */ -static uart_isr_ctx_t uart_config; - -/** - * @brief Allocate memory to store the callback functions. - */ -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; - - /* power on the UART device */ - NRF_UART0->POWER = 1; - /* reset configuration registers */ - NRF_UART0->CONFIG = 0; - /* configure RX/TX pin modes */ - NRF_GPIO->DIRSET = (1 << UART_PIN_TX); - NRF_GPIO->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_GPIO->DIRSET = (1 << UART_PIN_RTS); - NRF_GPIO->DIRSET = (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(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) -{ - if (uart == 0) { - NRF_UART0->POWER = 1; - } -} - -void uart_poweroff(uart_t uart) -{ - if (uart == 0) { - NRF_UART0->POWER = 0; - } -} - -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(); - } -} diff --git a/cpu/nrf52/Makefile b/cpu/nrf52/Makefile index 21f0d18719..f6c26f69b7 100644 --- a/cpu/nrf52/Makefile +++ b/cpu/nrf52/Makefile @@ -2,6 +2,6 @@ MODULE = cpu # add a list of subdirectories, that should also be build -DIRS = periph $(RIOTCPU)/cortexm_common +DIRS = periph $(RIOTCPU)/cortexm_common $(RIOTCPU)/nrf5x_common include $(RIOTBASE)/Makefile.base diff --git a/cpu/nrf52/Makefile.include b/cpu/nrf52/Makefile.include index eb5d45d596..073024aac6 100644 --- a/cpu/nrf52/Makefile.include +++ b/cpu/nrf52/Makefile.include @@ -1,3 +1,5 @@ export CPU_ARCH = cortex-m4f +export CPU_FAM = nrf52 +include $(RIOTCPU)/nrf5x_common/Makefile.include include $(RIOTCPU)/Makefile.include.cortexm_common diff --git a/cpu/nrf5x_common/Makefile b/cpu/nrf5x_common/Makefile new file mode 100644 index 0000000000..e09377cd1e --- /dev/null +++ b/cpu/nrf5x_common/Makefile @@ -0,0 +1,3 @@ +DIRS = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/nrf5x_common/Makefile.include b/cpu/nrf5x_common/Makefile.include new file mode 100644 index 0000000000..2992156ed4 --- /dev/null +++ b/cpu/nrf5x_common/Makefile.include @@ -0,0 +1,6 @@ +# export the CPU family so we can differentiate between them in the code +FAM = $(shell echo $(CPU_FAM) | tr 'a-z-' 'A-Z_') +export CFLAGS += -DCPU_FAM_$(FAM) + +# export the common include directory +export INCLUDES += -I$(RIOTCPU)/nrf5x_common/include diff --git a/cpu/nrf5x_common/doc.txt b/cpu/nrf5x_common/doc.txt new file mode 100644 index 0000000000..41687f4231 --- /dev/null +++ b/cpu/nrf5x_common/doc.txt @@ -0,0 +1,5 @@ +/** + * @defgroup cpu_nrf5x_common + * @ingroup cpu + * @brief Common implementations for the nRF5x family of CPUs + */ diff --git a/cpu/nrf52/include/periph_cpu.h b/cpu/nrf5x_common/include/periph_cpu.h similarity index 72% rename from cpu/nrf52/include/periph_cpu.h rename to cpu/nrf5x_common/include/periph_cpu.h index 31e3728565..58a745c025 100644 --- a/cpu/nrf52/include/periph_cpu.h +++ b/cpu/nrf5x_common/include/periph_cpu.h @@ -1,5 +1,5 @@ /* - * Copyright (C) 2016 Freie Universität Berlin + * Copyright (C) 2015-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 @@ -7,7 +7,7 @@ */ /** - * @ingroup cpu_nrf52 + * @ingroup cpu_nrf5x_common * @{ * * @file @@ -25,6 +25,34 @@ extern "C" { #endif +/** + * @brief Iron out some differences in register and IRQ channel naming between + * the different nRFx family members + * @{ + */ +#if defined(CPU_FAM_NRF51) +#define GPIO_BASE (NRF_GPIO) +#define UART_IRQN (UART0_IRQn) +#elif defined(CPU_FAM_NRF52) +#define GPIO_BASE (NRF_P0) +#define UART_IRQN (UARTE0_UART0_IRQn) +#else +#error "nrf5x_common: no valid value for CPU_FAM_XX defined" +#endif +/** @} */ + +/** + * @brief Length of the CPU_ID in octets + */ +#define CPUID_LEN (8U) + +/** + * @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) + /** * @brief Override GPIO pull register select values * @{ @@ -49,18 +77,6 @@ typedef enum { } 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) - -/** - * @brief Length of the CPU_ID in octets - */ -#define CPUID_LEN (8U) - #ifdef __cplusplus } #endif diff --git a/cpu/nrf5x_common/periph/Makefile b/cpu/nrf5x_common/periph/Makefile new file mode 100644 index 0000000000..6d1887b640 --- /dev/null +++ b/cpu/nrf5x_common/periph/Makefile @@ -0,0 +1,3 @@ +MODULE = periph + +include $(RIOTBASE)/Makefile.base diff --git a/cpu/nrf52/periph/cpuid.c b/cpu/nrf5x_common/periph/cpuid.c similarity index 71% rename from cpu/nrf52/periph/cpuid.c rename to cpu/nrf5x_common/periph/cpuid.c index 8cf45a550d..8e51e2c370 100644 --- a/cpu/nrf52/periph/cpuid.c +++ b/cpu/nrf5x_common/periph/cpuid.c @@ -1,6 +1,6 @@ /* - * Copyright (C) 2015 Jan Wagner - * 2016 Freie Universität Berlin + * Copyright (C) 2014-2016 Freie Universität Berlin + * 2015 Jan Wagner * * 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 @@ -8,13 +8,13 @@ */ /** - * @ingroup cpu_nrf52 + * @ingroup cpu_nrf5x_common * @{ * * @file * @brief CPUID interface implementation * - * The NRF52832 provides a 64-bit unique identifier, that is unique for each + * The NRF52832 provides a 64-bit unique identifier that is unique for each * shipped unit. * * @author Hauke Petersen diff --git a/cpu/nrf52/periph/gpio.c b/cpu/nrf5x_common/periph/gpio.c similarity index 72% rename from cpu/nrf52/periph/gpio.c rename to cpu/nrf5x_common/periph/gpio.c index 0a582fa28c..e8f7a84d06 100644 --- a/cpu/nrf52/periph/gpio.c +++ b/cpu/nrf5x_common/periph/gpio.c @@ -1,6 +1,6 @@ /* * Copyright (C) 2015 Jan Wagner - * 2016 Freie Universität Berlin + * 2015-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 @@ -8,15 +8,17 @@ */ /** - * @ingroup cpu_nrf52 + * @ingroup cpu_nrf5x_common * @{ * * @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! + * @note This GPIO driver implementation supports only one pin to be + * defined as external interrupt. * + * @author Christian Kühling + * @author Timo Ziegler * @author Hauke Petersen * @author Jan Wagner * @@ -27,6 +29,7 @@ #include "sched.h" #include "thread.h" #include "periph/gpio.h" +#include "periph_cpu.h" #include "periph_conf.h" /** @@ -38,11 +41,9 @@ 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]); + GPIO_BASE->PIN_CNF[pin] = ((dir << GPIO_PIN_CNF_DIR_Pos) | + (dir << GPIO_PIN_CNF_INPUT_Pos) | + (pullup << GPIO_PIN_CNF_PULL_Pos)); return 0; } @@ -81,35 +82,35 @@ void gpio_irq_disable(gpio_t pin) int gpio_read(gpio_t pin) { - if (NRF_P0->DIR & (1 << pin)) { - return (NRF_P0->OUT & (1 << pin)) ? 1 : 0; + if (GPIO_BASE->DIR & (1 << pin)) { + return (GPIO_BASE->OUT & (1 << pin)) ? 1 : 0; } else { - return (NRF_P0->IN & (1 << pin)) ? 1 : 0; + return (GPIO_BASE->IN & (1 << pin)) ? 1 : 0; } } void gpio_set(gpio_t pin) { - NRF_P0->OUTSET = (1 << pin); + GPIO_BASE->OUTSET = (1 << pin); } void gpio_clear(gpio_t pin) { - NRF_P0->OUTCLR = (1 << pin); + GPIO_BASE->OUTCLR = (1 << pin); } void gpio_toggle(gpio_t pin) { - NRF_P0->OUT ^= (1 << pin); + GPIO_BASE->OUT ^= (1 << pin); } void gpio_write(gpio_t pin, int value) { if (value) { - NRF_P0->OUTSET = (1 << pin); + GPIO_BASE->OUTSET = (1 << pin); } else { - NRF_P0->OUTCLR = (1 << pin); + GPIO_BASE->OUTCLR = (1 << pin); } } diff --git a/cpu/nrf52/periph/uart.c b/cpu/nrf5x_common/periph/uart.c similarity index 87% rename from cpu/nrf52/periph/uart.c rename to cpu/nrf5x_common/periph/uart.c index 8a27ec6434..42aaf6c309 100644 --- a/cpu/nrf52/periph/uart.c +++ b/cpu/nrf5x_common/periph/uart.c @@ -1,6 +1,7 @@ /* - * Copyright (C) 2015 Jan Wagner - * 2016 Freie Universität Berlin + * Copyright (C) 2014-2016 Freie Universität Berlin + * 2015 Jan Wagner + * * * 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 @@ -8,12 +9,14 @@ */ /** - * @ingroup cpu_nrf52 + * @ingroup cpu_nrf5x_common * @{ * * @file * @brief Implementation of the peripheral UART interface * + * @author Christian Kühling + * @author Timo Ziegler * @author Hauke Petersen * @author Jan Wagner * @@ -23,14 +26,15 @@ #include #include "cpu.h" -#include "thread.h" #include "sched.h" -#include "periph_conf.h" +#include "thread.h" #include "periph/uart.h" -#include "board.h" +#include "periph_cpu.h" +#include "periph_conf.h" + /** - * @brief Allocate memory to store the callback functions. + * @brief Allocate memory for the interrupt context */ static uart_isr_ctx_t uart_config; @@ -44,19 +48,23 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) uart_config.rx_cb = rx_cb; uart_config.arg = arg; +#ifdef CPU_FAM_NRF51 + /* power on the UART device */ + NRF_UART0->POWER = 1; +#endif /* 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); + GPIO_BASE->DIRSET = (1 << UART_PIN_TX); + GPIO_BASE->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); + GPIO_BASE->DIRSET = (1 << UART_PIN_RTS); + GPIO_BASE->DIRCLR = (1 << UART_PIN_CTS); /* configure RTS and CTS pins to use */ NRF_UART0->PSELRTS = UART_PIN_RTS; NRF_UART0->PSELCTS = UART_PIN_CTS; @@ -123,7 +131,7 @@ int uart_init(uart_t uart, uint32_t baudrate, uart_rx_cb_t rx_cb, void *arg) NRF_UART0->TASKS_STARTTX = 1; NRF_UART0->TASKS_STARTRX = 1; /* enable global and receiving interrupt */ - NVIC_EnableIRQ(UARTE0_UART0_IRQn); + NVIC_EnableIRQ(UART_IRQN); NRF_UART0->INTENSET = UART_INTENSET_RXDRDY_Msk; return 0; } @@ -142,7 +150,6 @@ void uart_write(uart_t uart, const uint8_t *data, size_t len) } } - void uart_poweron(uart_t uart) { (void)uart;