From 20f9515ed1b7fdf7cdd097e19ea0821e3f6cd86c Mon Sep 17 00:00:00 2001 From: Wojciech Bober Date: Sat, 9 Jan 2016 14:44:18 +0100 Subject: [PATCH] nrf52dk: cpu/nrf52832 support --- cpu/nrf52832/Makefile.nrf52832 | 262 ++++++++++++++++++ cpu/nrf52832/ble/ble-core.c | 238 +++++++++++++++++ cpu/nrf52832/ble/ble-core.h | 61 +++++ cpu/nrf52832/ble/ble-mac.c | 386 +++++++++++++++++++++++++++ cpu/nrf52832/ble/ble-mac.h | 53 ++++ cpu/nrf52832/dev/clock.c | 171 ++++++++++++ cpu/nrf52832/dev/lpm.h | 67 +++++ cpu/nrf52832/dev/random.c | 90 +++++++ cpu/nrf52832/dev/uart0.c | 118 ++++++++ cpu/nrf52832/dev/uart0.h | 57 ++++ cpu/nrf52832/dev/watchdog.c | 93 +++++++ cpu/nrf52832/erase.jlink | 2 + cpu/nrf52832/flash.jlink | 4 + cpu/nrf52832/ld/nrf52-pca10036-sd.ld | 12 + cpu/nrf52832/ld/nrf52-pca10040-sd.ld | 12 + cpu/nrf52832/ld/nrf52.ld | 12 + cpu/nrf52832/mtarch.h | 48 ++++ cpu/nrf52832/putchar.c | 70 +++++ cpu/nrf52832/rtimer-arch.c | 110 ++++++++ cpu/nrf52832/rtimer-arch.h | 52 ++++ 20 files changed, 1918 insertions(+) create mode 100644 cpu/nrf52832/Makefile.nrf52832 create mode 100644 cpu/nrf52832/ble/ble-core.c create mode 100644 cpu/nrf52832/ble/ble-core.h create mode 100644 cpu/nrf52832/ble/ble-mac.c create mode 100644 cpu/nrf52832/ble/ble-mac.h create mode 100644 cpu/nrf52832/dev/clock.c create mode 100644 cpu/nrf52832/dev/lpm.h create mode 100644 cpu/nrf52832/dev/random.c create mode 100644 cpu/nrf52832/dev/uart0.c create mode 100644 cpu/nrf52832/dev/uart0.h create mode 100644 cpu/nrf52832/dev/watchdog.c create mode 100644 cpu/nrf52832/erase.jlink create mode 100644 cpu/nrf52832/flash.jlink create mode 100644 cpu/nrf52832/ld/nrf52-pca10036-sd.ld create mode 100644 cpu/nrf52832/ld/nrf52-pca10040-sd.ld create mode 100644 cpu/nrf52832/ld/nrf52.ld create mode 100644 cpu/nrf52832/mtarch.h create mode 100644 cpu/nrf52832/putchar.c create mode 100644 cpu/nrf52832/rtimer-arch.c create mode 100644 cpu/nrf52832/rtimer-arch.h diff --git a/cpu/nrf52832/Makefile.nrf52832 b/cpu/nrf52832/Makefile.nrf52832 new file mode 100644 index 000000000..f93f063f3 --- /dev/null +++ b/cpu/nrf52832/Makefile.nrf52832 @@ -0,0 +1,262 @@ +ifndef NRF52_SDK_ROOT + $(error NRF52_SDK_ROOT not defined! You must specify where nRF52 SDK resides!) +endif + +ifneq ($(filter %.flash erase,$(MAKECMDGOALS)),) +ifeq ($(NRF52_JLINK_PATH),) +NRF52_JLINK_PATH=$(shell location=$$(which JLinkExe) && dirname $$location) +endif +ifeq ($(NRF52_JLINK_PATH),) + $(error JLink not found in PATH and NRF52_JLINK_PATH path is not defined) +endif +endif + +ifeq ($(CONTIKI_WITH_RIME),1) + $(error Rime stack is not supported!) +endif + +ifneq ($(CONTIKI_WITH_IPV6),1) + $(error Only IPv6 stack is supported!) +endif + +$(info SDK: $(NRF52_SDK_ROOT)) + +ifeq ($(NRF52_DK_REVISION),) +NRF52_DK_REVISION=pca10040 +endif + +ifneq ($(NRF52_WITHOUT_SOFTDEVICE),1) + ifeq ($(NRF52_SOFTDEVICE),) + NRF52_SOFTDEVICE := $(shell find $(NRF52_SDK_ROOT) -name *iot*_softdevice.hex | head -n 1) + endif + $(info SoftDevice: $(NRF52_SOFTDEVICE)) + LINKER_SCRIPT := $(CONTIKI_CPU)/ld/nrf52-$(NRF52_DK_REVISION)-sd.ld +else + LINKER_SCRIPT := $(CONTIKI_CPU)/ld/nrf52.ld +endif + +OUTPUT_FILENAME := $(CONTIKI_PROJECT) +MAKEFILE_NAME := $(MAKEFILE_LIST) +MAKEFILE_DIR := $(dir $(MAKEFILE_NAME) ) + +TEMPLATE_PATH = $(NRF52_SDK_ROOT)/components/toolchain/gcc + +OBJECT_DIRECTORY = $(OBJECTDIR) +LISTING_DIRECTORY := $(OBJECTDIR) +OUTPUT_BINARY_DIRECTORY := bin_$(TARGET) + +MK := mkdir +RM := rm -rf + +# Toolchain commands +CC := arm-none-eabi-gcc +AS := arm-none-eabi-as +AR := arm-none-eabi-ar +LD := arm-none-eabi-ld +NM := arm-none-eabi-nm +OBJDUMP := arm-none-eabi-objdump +OBJCOPY := arm-none-eabi-objcopy +SIZE := arm-none-eabi-size + +# JLink +JLINK := $(NRF52_JLINK_PATH)/JLinkExe +JLINK_OPTS = -Device NRF52 -if swd -speed 1000 +ifneq ($(NRF52_JLINK_SN),) +JLINK_OPTS += -SelectEmuBySN $(NRF52_JLINK_SN) +endif + +#function for removing duplicates in a list +remduplicates = $(strip $(if $1,$(firstword $1) $(call remduplicates,$(filter-out $(firstword $1),$1)))) + +### CPU-dependent directories +CONTIKI_CPU_DIRS += . dev ble #compat + +### CPU-dependent source files +CONTIKI_CPU_SOURCEFILES += clock.c rtimer-arch.c uart0.c putchar.c watchdog.c + +ifneq ($(NRF52_WITHOUT_SOFTDEVICE),1) +CONTIKI_CPU_SOURCEFILES += ble-core.c ble-mac.c +endif + +CONTIKI_SOURCEFILES += $(CONTIKI_CPU_SOURCEFILES) + +#source common to all targets +C_SOURCE_FILES += $(NRF52_SDK_ROOT)/components/drivers_nrf/common/nrf_drv_common.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/gpiote/nrf_drv_gpiote.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/rtc/nrf_drv_rtc.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/clock/nrf_drv_clock.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/timer/nrf_drv_timer.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/wdt/nrf_drv_wdt.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/rng/nrf_drv_rng.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/delay/nrf_delay.c \ + $(NRF52_SDK_ROOT)/components/drivers_nrf/uart/nrf_drv_uart.c \ + $(NRF52_SDK_ROOT)/components/libraries/util/app_error.c \ + $(NRF52_SDK_ROOT)/components/toolchain/system_nrf52.c + +ifneq ($(NRF52_WITHOUT_SOFTDEVICE),1) +C_SOURCE_FILES += $(NRF52_SDK_ROOT)/components/softdevice/common/softdevice_handler/softdevice_handler.c \ + $(NRF52_SDK_ROOT)/components/ble/common/ble_advdata.c +else +C_SOURCE_FILES += $(NRF52_SDK_ROOT)/components/libraries/fifo/app_fifo.c \ + $(NRF52_SDK_ROOT)/components/libraries/util/app_util_platform.c +endif + +#assembly files common to all targets +ASM_SOURCE_FILES = $(NRF52_SDK_ROOT)/components/toolchain/gcc/gcc_startup_nrf52.s + +#includes common to all targets +INC_PATHS += components/drivers_nrf/gpiote +INC_PATHS += components/drivers_nrf/hal +INC_PATHS += components/drivers_nrf/config +INC_PATHS += components/drivers_nrf/delay +INC_PATHS += components/drivers_nrf/uart +INC_PATHS += components/drivers_nrf/common +INC_PATHS += components/drivers_nrf/rtc +INC_PATHS += components/drivers_nrf/wdt +INC_PATHS += components/drivers_nrf/rng +INC_PATHS += components/drivers_nrf/clock +INC_PATHS += components/drivers_nrf/timer +INC_PATHS += components/libraries/util +INC_PATHS += components/libraries/timer +INC_PATHS += components/device +INC_PATHS += components/toolchain/gcc +INC_PATHS += components/toolchain +INC_PATHS += examples/bsp + +ifneq ($(NRF52_WITHOUT_SOFTDEVICE),1) +INC_PATHS += components/softdevice/s1xx_iot/headers +INC_PATHS += components/softdevice/s1xx_iot/headers/nrf52 +INC_PATHS += components/softdevice/common/softdevice_handler +INC_PATHS += components/ble/common +INC_PATHS += components/iot/common +INC_PATHS += components/iot/ble_ipsp +else +INC_PATHS += components/drivers_nrf/nrf_soc_nosd +INC_PATHS += components/libraries/fifo +endif + +EXTERNALDIRS += $(addprefix $(NRF52_SDK_ROOT)/, $(INC_PATHS)) + +# Sorting removes duplicates +BUILD_DIRECTORIES := $(sort $(OUTPUT_BINARY_DIRECTORY) $(LISTING_DIRECTORY)) + +# Clean files and directories +CLEAN += bin_$(TARGET) lst_$(TARGET) nrf52832.a *.elf *.hex + +#flags common to all targets +ifneq ($(NRF52_WITHOUT_SOFTDEVICE),1) +CFLAGS += -DSOFTDEVICE_PRESENT +CFLAGS += -DS132 +endif + +ifeq ($(SMALL),1) +CFLAGS += -Os +else +CFLAGS += -O2 +endif + +CFLAGS += -DNRF52 +CFLAGS += -DBOARD_$(shell echo $(NRF52_DK_REVISION) | tr a-z A-Z) +CFLAGS += -D__HEAP_SIZE=512 +CFLAGS += -DSWI_DISABLE0 +CFLAGS += -DCONFIG_GPIO_AS_PINRESET +CFLAGS += -DBLE_STACK_SUPPORT_REQD +CFLAGS += -mcpu=cortex-m4 +CFLAGS += -mthumb -mabi=aapcs --std=gnu99 +CFLAGS += -Wall -Werror +CFLAGS += -ggdb +CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 +# keep every function in separate section. This will allow linker to dump unused functions +CFLAGS += -ffunction-sections -fdata-sections -fno-strict-aliasing +CFLAGS += -fno-builtin --short-enums + +# keep every function in separate section. This will allow linker to dump unused functions +LDFLAGS += -Xlinker -Map=$(LISTING_DIRECTORY)/$(OUTPUT_FILENAME).map +LDFLAGS += -mthumb -mabi=aapcs -L $(TEMPLATE_PATH) -T$(LINKER_SCRIPT) +LDFLAGS += -mcpu=cortex-m4 +LDFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 +# let linker to dump unused sections +LDFLAGS += -Wl,--gc-sections +# use newlib in nano version +LDFLAGS += --specs=nano.specs -lc -lnosys + +# Assembler flags +ifneq ($(NRF52_WITHOUT_SOFTDEVICE),1) +ASMFLAGS += -DSOFTDEVICE_PRESENT +ASMFLAGS += -DS132 +endif +ASMFLAGS += -x assembler-with-cpp +ASMFLAGS += -DSWI_DISABLE0 +ASMFLAGS += -DNRF52 +ASMFLAGS += -DBOARD_$(shell echo $(NRF52_DK_REVISION) | tr a-z A-Z) +ASMFLAGS += -DCONFIG_GPIO_AS_PINRESET +ASMFLAGS += -DBLE_STACK_SUPPORT_REQD + +C_SOURCE_FILE_NAMES = $(notdir $(C_SOURCE_FILES)) +C_PATHS = $(call remduplicates, $(dir $(C_SOURCE_FILES) ) ) +C_OBJECTS = $(addprefix $(OBJECT_DIRECTORY)/, $(C_SOURCE_FILE_NAMES:.c=.o) ) + +ASM_SOURCE_FILE_NAMES = $(notdir $(ASM_SOURCE_FILES)) +ASM_PATHS = $(call remduplicates, $(dir $(ASM_SOURCE_FILES) )) +ASM_OBJECTS = $(addprefix $(OBJECT_DIRECTORY)/, $(ASM_SOURCE_FILE_NAMES:.s=.o) ) + +vpath %.c $(C_PATHS) +vpath %.s $(ASM_PATHS) + +OBJECTS = $(C_OBJECTS) $(ASM_OBJECTS) + +TARGET_LIBS= nrf52832.a $(NRF52_SDK_ROOT)/components/iot/ble_6lowpan/lib/ble_6lowpan.a + +### Don't treat the .elf as intermediate +.PRECIOUS: %.hex %.bin + +nrf52832.a: $(OBJECTS) + $(TRACE_AR) + $(Q)$(AR) $(AROPTS) $@ $^ + +### Compilation rules +CUSTOM_RULE_LINK=1 + +%.elf: $(TARGET_STARTFILES) %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a $(TARGET_LIBS) + $(TRACE_LD) + $(Q)$(CC) $(LDFLAGS) ${filter %o %.co %.a,$^} -o $@ + +# Assemble files +$(OBJECT_DIRECTORY)/%.o: %.s + @echo Compiling file: $(notdir $<) + $(Q)$(CC) $(ASMFLAGS) $(addprefix -I$(NRF52_SDK_ROOT)/, $(INC_PATHS)) -c -o $@ $< + +# Create binary file from the .out file +%.bin: %.elf + @echo Preparing: $@ + $(Q)$(OBJCOPY) -O binary $^ $@ + +# Create binary .hex file from the .out file +%.hex: %.elf + @echo Preparing: $@ + $(Q)$(OBJCOPY) -O ihex $^ $@ + +### We don't really need the .hex and .bin for the .$(TARGET) but let's make +### sure they get built +%.$(TARGET): %.elf %.hex %.bin + cp $*.elf $@ + $(Q)$(SIZE) $@ + +%.jlink: + sed -e 's/#OUTPUT_FILENAME#/$*.hex/' $(CONTIKI_CPU)/flash.jlink > $@ + +%.flash: %.hex %.jlink + @echo Flashing: $^ + $(JLINK) $(JLINK_OPTS) -CommanderScript $*.jlink + +softdevice.jlink: + sed -e 's,#OUTPUT_FILENAME#,$(NRF52_SOFTDEVICE),' $(CONTIKI_CPU)/flash.jlink > $@ + +softdevice.flash: softdevice.jlink + @echo Flashing: $(notdir $(NRF52_SOFTDEVICE)) + $(JLINK) $(JLINK_OPTS) -CommanderScript $^ + +erase: + $(JLINK) $(JLINK_OPTS) -CommanderScript $(CONTIKI_CPU)/erase.jlink + +.PHONY: softdevice.jlink diff --git a/cpu/nrf52832/ble/ble-core.c b/cpu/nrf52832/ble/ble-core.c new file mode 100644 index 000000000..cb3d4ce66 --- /dev/null +++ b/cpu/nrf52832/ble/ble-core.c @@ -0,0 +1,238 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup cpu + * @{ + * + * \addtogroup nrf52832 + * @{ + * + * \addtogroup nrf52832-ble Bluetooth Low Energy drivers + * @{ + * + * \file + * Basic BLE functions. + * \author + * Wojciech Bober + * + */ +#include +#include +#include "boards.h" +#include "nordic_common.h" +#include "nrf_delay.h" +#include "nrf_sdm.h" +#include "ble_advdata.h" +#include "ble_srv_common.h" +#include "ble_ipsp.h" +#include "softdevice_handler.h" +#include "app_error.h" +#include "iot_defines.h" +#include "ble-core.h" + +#define DEBUG 0 +#if DEBUG +#include +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif + +#define IS_SRVC_CHANGED_CHARACT_PRESENT 1 +#define APP_ADV_TIMEOUT 0 /**< Time for which the device must be advertising in non-connectable mode (in seconds). 0 disables timeout. */ +#define APP_ADV_ADV_INTERVAL MSEC_TO_UNITS(333, UNIT_0_625_MS) /**< The advertising interval. This value can vary between 100ms to 10.24s). */ + +static ble_gap_adv_params_t m_adv_params; /**< Parameters to be passed to the stack when starting advertising. */ + +static void +ble_evt_dispatch(ble_evt_t * p_ble_evt); +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize and enable the BLE stack. + */ +void +ble_stack_init(void) +{ + uint32_t err_code; + + // Enable BLE stack. + ble_enable_params_t ble_enable_params; + memset(&ble_enable_params, 0, sizeof(ble_enable_params)); + ble_enable_params.gatts_enable_params.attr_tab_size = + BLE_GATTS_ATTR_TAB_SIZE_DEFAULT; + ble_enable_params.gatts_enable_params.service_changed = + IS_SRVC_CHANGED_CHARACT_PRESENT; + err_code = sd_ble_enable(&ble_enable_params); + APP_ERROR_CHECK(err_code); + + // Register with the SoftDevice handler module for BLE events. + err_code = softdevice_ble_evt_handler_set(ble_evt_dispatch); + APP_ERROR_CHECK(err_code); + + // Setup address + ble_gap_addr_t ble_addr; + err_code = sd_ble_gap_address_get(&ble_addr); + APP_ERROR_CHECK(err_code); + + ble_addr.addr[5] = 0x00; + ble_addr.addr_type = BLE_GAP_ADDR_TYPE_PUBLIC; + + err_code = sd_ble_gap_address_set(BLE_GAP_ADDR_CYCLE_MODE_NONE, &ble_addr); + APP_ERROR_CHECK(err_code); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Return device EUI64 MAC address + * \param addr pointer to a buffer to store the address + */ +void +ble_get_mac(uint8_t addr[8]) +{ + uint32_t err_code; + ble_gap_addr_t ble_addr; + + err_code = sd_ble_gap_address_get(&ble_addr); + APP_ERROR_CHECK(err_code); + + IPV6_EUI64_CREATE_FROM_EUI48(addr, ble_addr.addr, ble_addr.addr_type); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize BLE advertising data. + * \param name Human readable device name that will be advertised + */ +void +ble_advertising_init(const char *name) +{ + uint32_t err_code; + ble_advdata_t advdata; + uint8_t flags = BLE_GAP_ADV_FLAG_BR_EDR_NOT_SUPPORTED; + ble_gap_conn_sec_mode_t sec_mode; + + BLE_GAP_CONN_SEC_MODE_SET_OPEN(&sec_mode); + + err_code = sd_ble_gap_device_name_set(&sec_mode, (const uint8_t *)name, + strlen(name)); + APP_ERROR_CHECK(err_code); + + ble_uuid_t adv_uuids[] = {{BLE_UUID_IPSP_SERVICE, BLE_UUID_TYPE_BLE}}; + + // Build and set advertising data. + memset(&advdata, 0, sizeof(advdata)); + + advdata.name_type = BLE_ADVDATA_FULL_NAME; + advdata.flags = flags; + advdata.uuids_complete.uuid_cnt = sizeof(adv_uuids) / sizeof(adv_uuids[0]); + advdata.uuids_complete.p_uuids = adv_uuids; + + err_code = ble_advdata_set(&advdata, NULL); + APP_ERROR_CHECK(err_code); + + // Initialize advertising parameters (used when starting advertising). + memset(&m_adv_params, 0, sizeof(m_adv_params)); + + m_adv_params.type = BLE_GAP_ADV_TYPE_ADV_IND; + m_adv_params.p_peer_addr = NULL; // Undirected advertisement. + m_adv_params.fp = BLE_GAP_ADV_FP_ANY; + m_adv_params.interval = APP_ADV_ADV_INTERVAL; + m_adv_params.timeout = APP_ADV_TIMEOUT; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Start BLE advertising. + */ +void +ble_advertising_start(void) +{ + uint32_t err_code; + + err_code = sd_ble_gap_adv_start(&m_adv_params); + APP_ERROR_CHECK(err_code); + + PRINTF("ble-core: advertising started\n"); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Print GAP address. + * \param addr a pointer to address + */ +void +ble_gap_addr_print(const ble_gap_addr_t *addr) +{ + unsigned int i; + for(i = 0; i < sizeof(addr->addr); i++) { + if(i > 0) { + PRINTF(":"); + }PRINTF("%02x", addr->addr[i]); + }PRINTF(" (%d)", addr->addr_type); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Function for handling the Application's BLE Stack events. + * \param[in] p_ble_evt Bluetooth stack event. + */ +static void +on_ble_evt(ble_evt_t *p_ble_evt) +{ + switch(p_ble_evt->header.evt_id) { + case BLE_GAP_EVT_CONNECTED: + PRINTF("ble-core: connected [handle:%d, peer: ", p_ble_evt->evt.gap_evt.conn_handle); + ble_gap_addr_print(&(p_ble_evt->evt.gap_evt.params.connected.peer_addr)); + PRINTF("]\n"); + sd_ble_gap_rssi_start(p_ble_evt->evt.gap_evt.conn_handle, + BLE_GAP_RSSI_THRESHOLD_INVALID, + 0); + break; + + case BLE_GAP_EVT_DISCONNECTED: + PRINTF("ble-core: disconnected [handle:%d]\n", p_ble_evt->evt.gap_evt.conn_handle); + ble_advertising_start(); + break; + default: + break; + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief SoftDevice BLE event callback. + * \param[in] p_ble_evt Bluetooth stack event. + */ +static void +ble_evt_dispatch(ble_evt_t *p_ble_evt) +{ + ble_ipsp_evt_handler(p_ble_evt); + on_ble_evt(p_ble_evt); +} +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + * @} + */ diff --git a/cpu/nrf52832/ble/ble-core.h b/cpu/nrf52832/ble/ble-core.h new file mode 100644 index 000000000..84c181d2e --- /dev/null +++ b/cpu/nrf52832/ble/ble-core.h @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup cpu + * @{ + * + * \addtogroup nrf52832 + * @{ + * + * \addtogroup nrf52832-ble Bluetooth Low Energy drivers + * @{ + * + * \file + * Basic BLE functions. + * \author + * Wojciech Bober + */ +#ifndef DEV_BLE_H_ +#define DEV_BLE_H_ + +#include + +void ble_stack_init(void); +void ble_advertising_init(const char *name); +void ble_advertising_start(void); +void ble_get_mac(uint8_t addr[8]); + +#endif /* DEV_BLE_H_ */ + +/** + * @} + * @} + * @} + */ diff --git a/cpu/nrf52832/ble/ble-mac.c b/cpu/nrf52832/ble/ble-mac.c new file mode 100644 index 000000000..6ffd87a82 --- /dev/null +++ b/cpu/nrf52832/ble/ble-mac.c @@ -0,0 +1,386 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832-ble + * @{ + * + * \file + * A MAC protocol implementation that uses nRF52 IPSP implementation + * as a link layer. + * \author + * Wojciech Bober + */ +#include +#include +#include "app_error.h" +#include "ble_ipsp.h" +#include "nrf_soc.h" +#include "iot_defines.h" + +#include "net/mac/nullmac.h" +#include "net/netstack.h" +#include "net/ip/uip.h" +#include "net/ip/tcpip.h" +#include "net/packetbuf.h" +#include "net/netstack.h" +#include "net/linkaddr.h" + +#include "dev/watchdog.h" + +#define DEBUG 0 +#if DEBUG +#include +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif + +#ifndef BLE_MAC_MAX_INTERFACE_NUM +#define BLE_MAC_MAX_INTERFACE_NUM 1 /**< Maximum number of interfaces, i.e., connection to master devices */ +#endif + +/*---------------------------------------------------------------------------*/ +process_event_t ble_event_interface_added; /**< This event is broadcast when BLE connection is established */ +process_event_t ble_event_interface_deleted; /**< This event is broadcast when BLE connection is destroyed */ + +/*---------------------------------------------------------------------------*/ +PROCESS(ble_ipsp_process, "BLE IPSP process"); + +/*---------------------------------------------------------------------------*/ +/** + * \brief A structure that binds IPSP connection with a peer address. + */ +typedef struct { + eui64_t peer_addr; + ble_ipsp_handle_t handle; +} ble_mac_interface_t; + +static ble_mac_interface_t interfaces[BLE_MAC_MAX_INTERFACE_NUM]; + +static volatile int busy_tx; /**< Flag is set to 1 when the driver is busy transmitting a packet. */ +static volatile int busy_rx; /**< Flag is set to 1 when there is a received packet pending. */ + +struct { + eui64_t src; + uint8_t payload[PACKETBUF_SIZE]; + uint16_t len; + int8_t rssi; +} input_packet; + +static mac_callback_t mac_sent_cb; +static void *mac_sent_ptr; + +/*---------------------------------------------------------------------------*/ +/** + * \brief Lookup interface by IPSP connection. + * + * \param handle a pointer to IPSP handle. + * \retval a pointer to interface structure + * \retval NULL if no interface has been found for a given handle + */ +static ble_mac_interface_t * +ble_mac_interface_lookup(ble_ipsp_handle_t *handle) +{ + int i; + for(i = 0; i < BLE_MAC_MAX_INTERFACE_NUM; i++) { + if(interfaces[i].handle.conn_handle == handle->conn_handle && + interfaces[i].handle.cid == handle->cid) { + return &interfaces[i]; + } + } + return NULL; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Add IPSP connection to the interface table. + * + * This function binds IPSP connection with peer address. + * + * \param peer a pointer to eui64 address + * \param handle a pointer to IPSP handle + * + * \retval a pointer to an interface structure on success + * \retval NULL if interface table is full + */ +static ble_mac_interface_t * +ble_mac_interface_add(eui64_t *peer, ble_ipsp_handle_t *handle) +{ + int i; + for(i = 0; i < BLE_MAC_MAX_INTERFACE_NUM; i++) { + if(interfaces[i].handle.conn_handle == 0 && interfaces[i].handle.cid == 0) { + memcpy(&interfaces[i].handle, handle, sizeof(ble_ipsp_handle_t)); + memcpy(&interfaces[i].peer_addr, peer, sizeof(eui64_t)); + process_post(PROCESS_BROADCAST, ble_event_interface_added, NULL); + return &interfaces[i]; + } + } + return NULL; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Remove interface from the interface table. + * \param interface a pointer to interface + */ +static void +ble_mac_interface_delete(ble_mac_interface_t *interface) +{ + memset(interface, 0, sizeof(ble_mac_interface_t)); + process_post(PROCESS_BROADCAST, ble_event_interface_deleted, NULL); +} + +/*---------------------------------------------------------------------------*/ +/** + * \brief Callback registered with IPSP to receive asynchronous events from the module. + * \note This function is called from SoftDevice interrupt context. + * + * \param[in] p_handle Pointer to IPSP handle. + * \param[in] p_evt Pointer to specific event, generated by IPSP module. + * + * \return NRF_SUCCESS on success, otherwise NRF_ERROR_NO_MEM error. + */ +static uint32_t +ble_mac_ipsp_evt_handler_irq(ble_ipsp_handle_t *p_handle, ble_ipsp_evt_t *p_evt) +{ + uint32_t retval = NRF_SUCCESS; + + ble_mac_interface_t *p_instance = NULL; + p_instance = ble_mac_interface_lookup(p_handle); + + if(p_handle) { + PRINTF("ble-mac: IPSP event [handle:%d CID 0x%04X]\n", p_handle->conn_handle, p_handle->cid); + } + + switch(p_evt->evt_id) { + case BLE_IPSP_EVT_CHANNEL_CONNECTED: { + eui64_t peer_addr; + + PRINTF("ble-mac: channel connected\n"); + + IPV6_EUI64_CREATE_FROM_EUI48( + peer_addr.identifier, + p_evt->evt_param->params.ch_conn_request.peer_addr.addr, + p_evt->evt_param->params.ch_conn_request.peer_addr.addr_type); + + p_instance = ble_mac_interface_add(&peer_addr, p_handle); + + if(p_instance != NULL) { + PRINTF("ble-mac: added new IPSP interface\n"); + } else { + PRINTF("ble-mac: cannot add new interface. Table is full\n"); + ble_ipsp_disconnect(p_handle); + } + break; + } + + case BLE_IPSP_EVT_CHANNEL_DISCONNECTED: { + PRINTF("ble-mac: channel disconnected\n"); + if(p_instance != NULL) { + PRINTF("ble-mac: removed IPSP interface\n"); + ble_mac_interface_delete(p_instance); + } + break; + } + + case BLE_IPSP_EVT_CHANNEL_DATA_RX: { + PRINTF("ble-mac: data received\n"); + if(p_instance != NULL) { + if(busy_rx) { + PRINTF("ble-mac: packet dropped as input buffer is busy\n"); + break; + } + + if(p_evt->evt_param->params.ch_rx.len > PACKETBUF_SIZE) { + PRINTF("ble-mac: packet buffer is too small!\n"); + break; + } + + busy_rx = 1; + + input_packet.len = p_evt->evt_param->params.ch_rx.len; + memcpy(input_packet.payload, p_evt->evt_param->params.ch_rx.p_data, input_packet.len); + memcpy(input_packet.src.identifier, p_instance->peer_addr.identifier, sizeof(eui64_t)); + sd_ble_gap_rssi_get(p_handle->conn_handle, &input_packet.rssi); + + process_poll(&ble_ipsp_process); + } else { + PRINTF("ble-mac: got data to unknown interface!\n"); + } + break; + } + + case BLE_IPSP_EVT_CHANNEL_DATA_TX_COMPLETE: { + PRINTF("ble-mac: data transmitted\n"); + busy_tx = 0; + break; + } + } + + return retval; +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(ble_ipsp_process, ev, data) +{ + PROCESS_BEGIN(); + + while(1) { + PROCESS_WAIT_EVENT(); + if(ev == PROCESS_EVENT_POLL) { + packetbuf_copyfrom(input_packet.payload, input_packet.len); + packetbuf_set_attr(PACKETBUF_ATTR_RSSI, input_packet.rssi); + packetbuf_set_addr(PACKETBUF_ADDR_SENDER, (const linkaddr_t *)input_packet.src.identifier); + packetbuf_set_addr(PACKETBUF_ADDR_RECEIVER, &linkaddr_node_addr); + busy_rx = 0; + NETSTACK_LLSEC.input(); + } + } + + PROCESS_END(); +} + +/*---------------------------------------------------------------------------*/ +/** + * \brief Lookup IPSP handle by peer address. + * + * \param addr a pointer to eui64 address. + * \retval a pointer to IPSP handle on success + * \retval NULL if an IPSP handle for given address haven't been found + */ +static ble_ipsp_handle_t * +find_handle(const linkaddr_t *addr) +{ + int i; + for(i = 0; i < BLE_MAC_MAX_INTERFACE_NUM; i++) { + if(linkaddr_cmp((const linkaddr_t *)&interfaces[i].peer_addr, addr)) { + return &interfaces[i].handle; + } + } + return NULL; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Send packet on a given IPSP handle. + * + * \param handle a pointer to IPSP handle. + * \return 1 on success, 0 otherwise + */ +static int +send_to_peer(ble_ipsp_handle_t *handle) +{ + PRINTF("ble-mac: sending packet[GAP handle:%d CID:0x%04X]\n", handle->conn_handle, handle->cid); + return (ble_ipsp_send(handle, packetbuf_dataptr(), packetbuf_datalen()) == NRF_SUCCESS); +} +/*---------------------------------------------------------------------------*/ +static void +send_packet(mac_callback_t sent, void *ptr) +{ + int i; + const linkaddr_t *dest; + ble_ipsp_handle_t *handle; + int ret = 0; + + mac_sent_cb = sent; + mac_sent_ptr = ptr; + + dest = packetbuf_addr(PACKETBUF_ADDR_RECEIVER); + + if(linkaddr_cmp(dest, &linkaddr_null)) { + for(i = 0; i < BLE_MAC_MAX_INTERFACE_NUM; i++) { + if(interfaces[i].handle.cid != 0 && interfaces[i].handle.conn_handle != 0) { + ret = send_to_peer(&interfaces[i].handle); + watchdog_periodic(); + } + } + } else if((handle = find_handle(dest)) != NULL) { + ret = send_to_peer(handle); + } else { + PRINTF("ble-mac: no connection found for peer"); + } + + if(ret) { + busy_tx = 1; + while(busy_tx) { + watchdog_periodic(); + sd_app_evt_wait(); + } + mac_call_sent_callback(sent, ptr, MAC_TX_OK, 1); + } else { + mac_call_sent_callback(sent, ptr, MAC_TX_ERR, 1); + } +} +/*---------------------------------------------------------------------------*/ +static int +on(void) +{ + return 1; +} +/*---------------------------------------------------------------------------*/ +static int +off(int keep_radio_on) +{ + return 1; +} +/*---------------------------------------------------------------------------*/ +static unsigned short +channel_check_interval(void) +{ + return 0; +} +/*---------------------------------------------------------------------------*/ +static void +init(void) +{ +// Initialize IPSP service + uint32_t err_code; + ble_ipsp_init_t ipsp_init_params; + + memset(&ipsp_init_params, 0, sizeof(ipsp_init_params)); + ipsp_init_params.evt_handler = ble_mac_ipsp_evt_handler_irq; + err_code = ble_ipsp_init(&ipsp_init_params); + APP_ERROR_CHECK(err_code); + + ble_event_interface_added = process_alloc_event(); + ble_event_interface_deleted = process_alloc_event(); + + process_start(&ble_ipsp_process, NULL); +} +/*---------------------------------------------------------------------------*/ +const struct mac_driver ble_ipsp_mac_driver = { + "nRF52 IPSP driver", + init, + send_packet, + NULL, + on, + off, + channel_check_interval, +}; +/*---------------------------------------------------------------------------*/ +/** + * @} + */ diff --git a/cpu/nrf52832/ble/ble-mac.h b/cpu/nrf52832/ble/ble-mac.h new file mode 100644 index 000000000..3dd9b82af --- /dev/null +++ b/cpu/nrf52832/ble/ble-mac.h @@ -0,0 +1,53 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832-ble + * @{ + * + * \file + * A MAC protocol implementation that uses nRF52 IPSP implementation + * as a link layer. + * \author + * Wojciech Bober + */ +#ifndef BLE_MAC_H_ +#define BLE_MAC_H_ + +#include "sys/process.h" +#include "net/mac/mac.h" + +extern const struct mac_driver ble_ipsp_mac_driver; /**< BLE over IPSP MAC driver structure */ +extern process_event_t ble_event_interface_added; /**< This event is broadcast when a new IPSP connection is established */ +extern process_event_t ble_event_interface_deleted; /**< This event is broadcast when a IPSP connection is deleted */ + +#endif /* BLE_MAC_H_ */ +/** + * @} + */ diff --git a/cpu/nrf52832/dev/clock.c b/cpu/nrf52832/dev/clock.c new file mode 100644 index 000000000..4ee09839d --- /dev/null +++ b/cpu/nrf52832/dev/clock.c @@ -0,0 +1,171 @@ +/* + * Copyright (c) 2015 Nordic Semiconductor. All Rights Reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED + * OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \addtogroup nrf52832 + * @{ + * + * \addtogroup nrf52832-dev Device drivers + * @{ + * + * \addtogroup nrf52832-clock Clock driver + * @{ + * + * \file + * Software clock implementation for the nRF52. + * \author + * Wojciech Bober + * + */ +/*---------------------------------------------------------------------------*/ +#include +#include +#include "nrf.h" +#include "nrf_drv_config.h" +#include "nrf_drv_rtc.h" +#include "nrf_drv_clock.h" +#include "nrf_delay.h" +#include "app_error.h" +#include "contiki.h" +#include "platform-conf.h" + +/*---------------------------------------------------------------------------*/ +const nrf_drv_rtc_t rtc = NRF_DRV_RTC_INSTANCE(PLATFORM_RTC_INSTANCE_ID); /**< RTC instance used for platform clock */ +/*---------------------------------------------------------------------------*/ +static volatile uint32_t ticks; +void clock_update(void); + +#define TICKS (RTC1_CONFIG_FREQUENCY/CLOCK_CONF_SECOND) + +/** + * \brief Function for handling the RTC0 interrupts + * \param int_type Type of interrupt to be handled + */ +static void +rtc_handler(nrf_drv_rtc_int_type_t int_type) +{ + if (int_type == NRF_DRV_RTC_INT_TICK) { + clock_update(); + } +} + +#ifndef SOFTDEVICE_PRESENT +/** \brief Function starting the internal LFCLK XTAL oscillator. + */ +static void +lfclk_config(void) +{ + ret_code_t err_code = nrf_drv_clock_init(NULL); + APP_ERROR_CHECK(err_code); + + nrf_drv_clock_lfclk_request(); +} +#endif + +/** + * \brief Function initialization and configuration of RTC driver instance. + */ +static void +rtc_config(void) +{ + uint32_t err_code; + + //Initialize RTC instance + err_code = nrf_drv_rtc_init(&rtc, NULL, rtc_handler); + APP_ERROR_CHECK(err_code); + + //Enable tick event & interrupt + nrf_drv_rtc_tick_enable(&rtc, true); + + //Power on RTC instance + nrf_drv_rtc_enable(&rtc); +} +/*---------------------------------------------------------------------------*/ +void +clock_init(void) +{ + ticks = 0; +#ifndef SOFTDEVICE_PRESENT + lfclk_config(); +#endif + rtc_config(); +} +/*---------------------------------------------------------------------------*/ +CCIF clock_time_t +clock_time(void) +{ + return (clock_time_t)(ticks & 0xFFFFFFFF); +} +/*---------------------------------------------------------------------------*/ +void +clock_update(void) +{ + ticks++; + if (etimer_pending()) { + etimer_request_poll(); + } +} +/*---------------------------------------------------------------------------*/ +CCIF unsigned long +clock_seconds(void) +{ + return (unsigned long)ticks/CLOCK_CONF_SECOND; +} +/*---------------------------------------------------------------------------*/ +void +clock_wait(clock_time_t i) +{ + clock_time_t start; + start = clock_time(); + while (clock_time() - start < (clock_time_t)i) { + __WFE(); + } +} +/*---------------------------------------------------------------------------*/ +void +clock_delay_usec(uint16_t dt) +{ + nrf_delay_us(dt); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Obsolete delay function but we implement it here since some code + * still uses it + */ +void +clock_delay(unsigned int i) +{ + clock_delay_usec(i); +} +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + * @} + */ diff --git a/cpu/nrf52832/dev/lpm.h b/cpu/nrf52832/dev/lpm.h new file mode 100644 index 000000000..192165a49 --- /dev/null +++ b/cpu/nrf52832/dev/lpm.h @@ -0,0 +1,67 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832-dev Device drivers + * @{ + * + * \addtogroup nrf52832-lpm Low power mode functions + * @{ + * + * \file + * A header file for low power mode functions. + * \author + * Wojciech Bober + */ +#ifndef LPM_H +#define LPM_H + +#ifdef SOFTDEVICE_PRESENT +#include "nrf_soc.h" +#endif + +/** + * \brief Stop and wait for an event + * + */ +static inline void +lpm_drop(void) +{ +#ifdef SOFTDEVICE_PRESENT + sd_app_evt_wait(); +#else + __WFI(); +#endif +} + +#endif /* DEV_LPM_H_ */ +/** + * @} + * @} + */ diff --git a/cpu/nrf52832/dev/random.c b/cpu/nrf52832/dev/random.c new file mode 100644 index 000000000..d21bf18ff --- /dev/null +++ b/cpu/nrf52832/dev/random.c @@ -0,0 +1,90 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832 + * @{ + * + * \addtogroup nrf52832-dev Device drivers + * @{ + * + * \addtogroup nrf52832-rng Hardware random number generator + * @{ + * + * \file + * Random number generator routines exploiting the nRF52 hardware + * capabilities. + * + * This file overrides core/lib/random.c. + * + * \author + * Wojciech Bober + */ +#include +#include +#include "app_error.h" +/*---------------------------------------------------------------------------*/ +/** + * \brief Generates a new random number using the nRF52 RNG. + * \return a random number. + */ +unsigned short +random_rand(void) +{ + unsigned short value = 42; + uint8_t available; + ret_code_t err_code; + + do { + nrf_drv_rng_bytes_available(&available); + } while (available < sizeof(value)); + + err_code = nrf_drv_rng_rand((uint8_t *)&value, sizeof(value)); + APP_ERROR_CHECK(err_code); + + return value; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize the nRF52 random number generator. + * \param seed Ignored. It's here because the function prototype is in core. + * + */ +void +random_init(unsigned short seed) +{ + (void)seed; + ret_code_t err_code = nrf_drv_rng_init(NULL); + APP_ERROR_CHECK(err_code); +} +/** + * @} + * @} + * @} + */ diff --git a/cpu/nrf52832/dev/uart0.c b/cpu/nrf52832/dev/uart0.c new file mode 100644 index 000000000..df9c7b9e3 --- /dev/null +++ b/cpu/nrf52832/dev/uart0.c @@ -0,0 +1,118 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832-dev Device drivers + * @{ + * + * \addtogroup nrf52832-uart UART driver + * @{ + * + * \file + * Contiki compatible UART driver. + * \author + * Wojciech Bober + */ +#include +#include "nrf.h" +#include "nrf_drv_config.h" +#include "nrf_drv_uart.h" +#include "app_util_platform.h" +#include "app_error.h" + +#include "contiki.h" +#include "dev/uart0.h" +#include "dev/watchdog.h" +#include "lib/ringbuf.h" + +#define TXBUFSIZE 128 +static uint8_t rx_buffer[1]; + +static int (*uart0_input_handler)(unsigned char c); + +static struct ringbuf txbuf; +static uint8_t txbuf_data[TXBUFSIZE]; + +/*---------------------------------------------------------------------------*/ +static void +uart_event_handler(nrf_drv_uart_event_t * p_event, void * p_context) +{ + ENERGEST_ON(ENERGEST_TYPE_IRQ); + + if (p_event->type == NRF_DRV_UART_EVT_RX_DONE) { + if (uart0_input_handler != NULL) { + uart0_input_handler(p_event->data.rxtx.p_data[0]); + } + (void)nrf_drv_uart_rx(rx_buffer, 1); + } else if (p_event->type == NRF_DRV_UART_EVT_TX_DONE) { + if (ringbuf_elements(&txbuf) > 0) { + uint8_t c = ringbuf_get(&txbuf); + nrf_drv_uart_tx(&c, 1); + } + } + + ENERGEST_OFF(ENERGEST_TYPE_IRQ); +} +/*---------------------------------------------------------------------------*/ +void +uart0_set_input(int (*input)(unsigned char c)) +{ + uart0_input_handler = input; +} +/*---------------------------------------------------------------------------*/ +void +uart0_writeb(unsigned char c) +{ + if (nrf_drv_uart_tx(&c, 1) == NRF_ERROR_BUSY) { + while (ringbuf_put(&txbuf, c) == 0) { + __WFE(); + } + } +} +/*---------------------------------------------------------------------------*/ +/** + * Initialize the RS232 port. + * + */ +void +uart0_init(unsigned long ubr) +{ + nrf_drv_uart_config_t config = NRF_DRV_UART_DEFAULT_CONFIG; + ret_code_t retcode = nrf_drv_uart_init(&config, uart_event_handler); + APP_ERROR_CHECK(retcode); + + ringbuf_init(&txbuf, txbuf_data, sizeof(txbuf_data)); + + nrf_drv_uart_rx_enable(); + nrf_drv_uart_rx(rx_buffer, 1); +} +/** + * @} + * @} + */ diff --git a/cpu/nrf52832/dev/uart0.h b/cpu/nrf52832/dev/uart0.h new file mode 100644 index 000000000..c6b3938ea --- /dev/null +++ b/cpu/nrf52832/dev/uart0.h @@ -0,0 +1,57 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832-dev Device drivers + * @{ + * + * \addtogroup nrf52832-uart UART driver + * @{ + * + * \file + * A header file for Contiki compatible UART driver. + * \author + * Wojciech Bober + */ +#ifndef UART_0_H +#define UART_0_H + +#include +#include "contiki-conf.h" + +void uart0_init(); +void uart0_writeb(uint8_t byte); + +void uart0_set_input(int (* input)(unsigned char c)); + +#endif /* UART_0_H */ +/** + * @} + * @} + */ diff --git a/cpu/nrf52832/dev/watchdog.c b/cpu/nrf52832/dev/watchdog.c new file mode 100644 index 000000000..50e26d72b --- /dev/null +++ b/cpu/nrf52832/dev/watchdog.c @@ -0,0 +1,93 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832-dev Device drivers + * @{ + * + * \addtogroup nrf52832-watchdog Watchdog driver + * @{ + * + * \file + * Contiki compatible watchdog driver implementation. + * \author + * Wojciech Bober + */ +#include +#include "app_error.h" +#include "contiki-conf.h" + +static nrf_drv_wdt_channel_id wdt_channel_id; +static uint8_t wdt_initialized = 0; + +/** + * \brief WDT events handler. + */ +static void wdt_event_handler(void) +{ + LEDS_OFF(LEDS_MASK); +} + +/*---------------------------------------------------------------------------*/ +void +watchdog_init(void) +{ + ret_code_t err_code; + err_code = nrf_drv_wdt_init(NULL, &wdt_event_handler); + APP_ERROR_CHECK(err_code); + err_code = nrf_drv_wdt_channel_alloc(&wdt_channel_id); + APP_ERROR_CHECK(err_code); + wdt_initialized = 1; +} +/*---------------------------------------------------------------------------*/ +void +watchdog_start(void) +{ + if(wdt_initialized) { + nrf_drv_wdt_enable(); + } +} +/*---------------------------------------------------------------------------*/ +void +watchdog_periodic(void) +{ + if(wdt_initialized) { + nrf_drv_wdt_channel_feed(wdt_channel_id); + } +} +/*---------------------------------------------------------------------------*/ +void +watchdog_reboot(void) +{ + NVIC_SystemReset(); +} +/** + * @} + * @} + */ diff --git a/cpu/nrf52832/erase.jlink b/cpu/nrf52832/erase.jlink new file mode 100644 index 000000000..5f08d8d86 --- /dev/null +++ b/cpu/nrf52832/erase.jlink @@ -0,0 +1,2 @@ +erase +q \ No newline at end of file diff --git a/cpu/nrf52832/flash.jlink b/cpu/nrf52832/flash.jlink new file mode 100644 index 000000000..787670d55 --- /dev/null +++ b/cpu/nrf52832/flash.jlink @@ -0,0 +1,4 @@ +loadfile #OUTPUT_FILENAME# +r +g +q \ No newline at end of file diff --git a/cpu/nrf52832/ld/nrf52-pca10036-sd.ld b/cpu/nrf52832/ld/nrf52-pca10036-sd.ld new file mode 100644 index 000000000..455749e29 --- /dev/null +++ b/cpu/nrf52832/ld/nrf52-pca10036-sd.ld @@ -0,0 +1,12 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x1f000, LENGTH = 0x61000 + RAM (rwx) : ORIGIN = 0x08000000, LENGTH = 0x8000 +} + +INCLUDE "nrf5x_common.ld" \ No newline at end of file diff --git a/cpu/nrf52832/ld/nrf52-pca10040-sd.ld b/cpu/nrf52832/ld/nrf52-pca10040-sd.ld new file mode 100644 index 000000000..f30aad455 --- /dev/null +++ b/cpu/nrf52832/ld/nrf52-pca10040-sd.ld @@ -0,0 +1,12 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x1f000, LENGTH = 0x61000 + RAM (rwx) : ORIGIN = 0x20002800, LENGTH = 0xD800 +} + +INCLUDE "nrf5x_common.ld" \ No newline at end of file diff --git a/cpu/nrf52832/ld/nrf52.ld b/cpu/nrf52832/ld/nrf52.ld new file mode 100644 index 000000000..268794d04 --- /dev/null +++ b/cpu/nrf52832/ld/nrf52.ld @@ -0,0 +1,12 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x0, LENGTH = 0x80000 + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x8000 +} + +INCLUDE "nrf5x_common.ld" \ No newline at end of file diff --git a/cpu/nrf52832/mtarch.h b/cpu/nrf52832/mtarch.h new file mode 100644 index 000000000..4f696669d --- /dev/null +++ b/cpu/nrf52832/mtarch.h @@ -0,0 +1,48 @@ +/* + * Copyright (c) 2010, Loughborough University - Computer Science + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. The name of the author may not be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS + * OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE + * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + */ +/* + * \file + * Stub header file for multi-threading. It doesn't do anything, it + * just exists so that mt.c can compile cleanly. + * + * This is based on the original mtarch.h for z80 by Takahide Matsutsuka + * + * \author + * George Oikonomou - + */ +#ifndef __MTARCH_H__ +#define __MTARCH_H__ + +struct mtarch_thread { + unsigned char *sp; +}; + +#endif /* __MTARCH_H__ */ diff --git a/cpu/nrf52832/putchar.c b/cpu/nrf52832/putchar.c new file mode 100644 index 000000000..c4163ba3d --- /dev/null +++ b/cpu/nrf52832/putchar.c @@ -0,0 +1,70 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832 + * @{ + * + * \file + * Hardware specific implementation of putchar() and puts() functions. + * \author + * Wojciech Bober + * + */ +/*---------------------------------------------------------------------------*/ +#include +#include "dev/uart0.h" +/*---------------------------------------------------------------------------*/ +int +putchar(int c) +{ + uart0_writeb(c); + return c; +} +/*---------------------------------------------------------------------------*/ +int +puts(const char *str) +{ + int i; + + if (str == NULL) { + return 0; + } + + for (i = 0; i < strlen(str); i++) { + uart0_writeb(str[i]); + } + + uart0_writeb('\n'); + return i; +} +/*---------------------------------------------------------------------------*/ +/** + * @} + */ diff --git a/cpu/nrf52832/rtimer-arch.c b/cpu/nrf52832/rtimer-arch.c new file mode 100644 index 000000000..78f4790f2 --- /dev/null +++ b/cpu/nrf52832/rtimer-arch.c @@ -0,0 +1,110 @@ +/* + * Copyright (c) 2015 Nordic Semiconductor. All Rights Reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED + * OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \addtogroup nrf52832 + * @{ + * + * \file + * Implementation of the architecture dependent rtimer functions for the nRF52 + * + * \author + * Wojciech Bober + */ +/*---------------------------------------------------------------------------*/ +#include +#include +#include "nrf.h" +#include "nrf_drv_timer.h" +#include "app_error.h" +#include "contiki.h" +#include "platform-conf.h" + +static const nrf_drv_timer_t timer = NRF_DRV_TIMER_INSTANCE(PLATFORM_TIMER_INSTANCE_ID); /**< Timer instance used for rtimer */ + +/** + * \brief Handler for timer events. + * + * \param event_type type of an event that should be handled + * \param p_context opaque data pointer passed from nrf_drv_timer_init() + */ +static void +timer_event_handler(nrf_timer_event_t event_type, void* p_context) +{ + switch (event_type) { + case NRF_TIMER_EVENT_COMPARE1: + rtimer_run_next(); + break; + + default: + //Do nothing. + break; + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize platform rtimer + */ +void +rtimer_arch_init(void) +{ + ret_code_t err_code = nrf_drv_timer_init(&timer, NULL, timer_event_handler); + APP_ERROR_CHECK(err_code); + nrf_drv_timer_enable(&timer); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Schedules an rtimer task to be triggered at time t + * \param t The time when the task will need executed. + * + * \e t is an absolute time, in other words the task will be executed AT + * time \e t, not IN \e t rtimer ticks. + * + * This function schedules a one-shot event with the nRF RTC. + */ +void +rtimer_arch_schedule(rtimer_clock_t t) +{ + nrf_drv_timer_compare(&timer, NRF_TIMER_CC_CHANNEL1, t, true); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns the current real-time clock time + * \return The current rtimer time in ticks + * + */ +rtimer_clock_t +rtimer_arch_now() +{ + return nrf_drv_timer_capture(&timer, NRF_TIMER_CC_CHANNEL0); +} +/*---------------------------------------------------------------------------*/ +/** + * @} + */ diff --git a/cpu/nrf52832/rtimer-arch.h b/cpu/nrf52832/rtimer-arch.h new file mode 100644 index 000000000..da709dae2 --- /dev/null +++ b/cpu/nrf52832/rtimer-arch.h @@ -0,0 +1,52 @@ +/* + * Copyright (c) 2015, Nordic Semiconductor + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the Institute nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY + * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * + */ +/** + * \addtogroup nrf52832 nRF52832 + * @{ + * + * \file + * Architecture dependent rtimer implementation header file. + * \author + * Wojciech Bober + * + */ +/*---------------------------------------------------------------------------*/ +#ifndef RTIMER_ARCH_H_ +#define RTIMER_ARCH_H_ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +/*---------------------------------------------------------------------------*/ +rtimer_clock_t rtimer_arch_now(void); +/*---------------------------------------------------------------------------*/ +#endif /* RTIMER_ARCH_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + */