This commit is contained in:
Daniel Tralamazza 2016-06-22 22:34:11 +02:00
parent 805f7ea2f2
commit 28769f2609
26 changed files with 1709 additions and 0 deletions

1
nrf52/.gitignore vendored Normal file
View File

@ -0,0 +1 @@
build/

141
nrf52/Makefile Normal file
View File

@ -0,0 +1,141 @@
include ../py/mkenv.mk
CROSS_COMPILE ?= arm-none-eabi-
BTYPE ?= debug
ifeq (${BTYPE}, release)
DEFINES += NDEBUG
CFLAGS += -Os
# CFLAGS += -flto
else
ifeq (${BTYPE}, debug)
DEBUG := 1
DEFINES += DEBUG
CFLAGS += -Og -g
else
$(error Invalid BTYPE specified)
endif
endif
BOARD ?= PCA10040
BUILD = build/${BOARD}/${BTYPE}
LINKER_PATH = .
LINKER_SCRIPT = gcc_nrf52_s132.ld
# don't set PROG as it's used by mkrules.mk
PROGRAM ?= ${BUILD}/firmware
# qstr definitions (must come before including py.mk)
QSTR_DEFS = qstrdefsport.h
# include py core make definitions
include ../py/py.mk
ifeq ($(wildcard boards/${BOARD}/.),)
$(error Invalid BOARD specified)
else
# include board makefile (if any)
-include boards/${BOARD}/build.mk
endif
# include nordic makefile
include nordic/build.mk
SRC_C += \
main.c \
mp_functions.c \
nrf52_app_error.c \
nrf52_ble.c \
lib/mp-readline/readline.c \
lib/utils/pyexec.c \
lib/utils/stdout_helpers.c
# XXX I simply copied gcc_startup_nrf52.s to .S so mkrules can compile it
OBJ += $(PY_O) $(addprefix ${BUILD}/, $(SRC_C:.c=.o))
INC += -I.
INC += -I..
INC += -I${BUILD}
INC += -Iboards/${BOARD}
INC += -I../lib/mp-readline
# transform all DEFINES entry in -DDEFINE c flags
CFLAGS += $(patsubst %,-D%,${DEFINES})
CFLAGS += ${INC}
CFLAGS += -Wall -Werror -std=gnu99
CFLAGS += -mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mabi=aapcs -fsingle-precision-constant
CFLAGS += -ffunction-sections -fdata-sections -fno-strict-aliasing
CFLAGS += -fno-builtin --short-enums
LDFLAGS += -Wl,-Map=${PROGRAM}.map
LDFLAGS += -mthumb -mabi=aapcs -L${LINKER_PATH} -T${LINKER_SCRIPT}
LDFLAGS += -mcpu=cortex-m4
LDFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16
LDFLAGS += -Wl,--gc-sections
LDFLAGS += --specs=nano.specs -lc -lnosys
# mkenv doesn't set these
OBJDUMP = $(CROSS_COMPILE)objdump
GDB = $(CROSS_COMPILE)gdb
all: ${PROGRAM}.hex ${PROGRAM}.bin
.PHONY: all
${PROGRAM}.elf: ${OBJ}
$(ECHO) "LINK $@"
${Q}${CC} -o $@ ${CFLAGS} ${LDFLAGS} $^ ${LDLIBS}
ifndef DEBUG
${Q}$(STRIP) $(STRIPFLAGS_EXTRA) $@
endif
${Q}$(SIZE) $@
%.hex: %.elf
${Q}${OBJCOPY} -O ihex $< $@
%.bin: %.elf
${Q}${OBJCOPY} -O binary $< $@
%.jlink: %.hex
${OBJDUMP} -h $< | \
awk '$$1 ~ /^[0-9]+$$/ {addr="0x"$$5; if (!min || addr < min) min = addr} END { printf "\
loadbin %s,%s\n\
sleep 100\n\
r\n\
g\n\
exit\n", f, min}' f="$<" > $@
%-all.jlink: %.jlink ${SOFTDEV_HEX}
@[ -e "${SOFTDEV_HEX}" ] || echo "cannot find softdevice hex image '${SOFTDEV_HEX}'" >&2
# w4 0x4001e504, 0x2 -> enable erase: CONFIG.WEN = EEN
# w4 0x4001e50c, 0x1 -> erase all: ERASEALL = 1
printf "\
device nrf52\n\
halt\n\
w4 0x4001e504, 0x2\n\
w4 0x4001e50c, 0x1\n\
sleep 100\n\
r\n\
loadbin %s,0\n" ${SOFTDEV_HEX} > $@
cat $< >> $@
flash: ${PROGRAM}.hex ${PROGRAM}.jlink
JLinkExe -device nrf52 -if SWD ${PROGRAM}.jlink
.PHONY: flash
flash-all: ${PROGRAM}.hex ${PROGRAM}-all.jlink
JLinkExe -device nrf52 -if SWD ${PROGRAM}-all.jlink
.PHONY: flash-all
gdbserver: ${PROGRAM}.elf
JLinkGDBServer -device nrf52 -if SWD
.PHONY: gdbserver
gdb: ${PROGRAM}.elf
${GDB} ${PROGRAM}.elf -ex 'target remote :2331'
.PHONY: gdb
include ../py/mkrules.mk

46
nrf52/README.md Normal file
View File

@ -0,0 +1,46 @@
# nRF52 Port
WIP
## requirements
- GNU make
- ARM GCC for embedded development
- JLink Segger command line tools
- Download and unzip the Nordic SDK 11 under `nordic/`
## quickstart
Plug your board and type:
$> make flash-all
## debugging
$> make gdbserver
in another terminal
$> make gdb
in yet another terminal (for the RTT messages)
$> telnet 127.0.0.1 19021
## TODO
- BLE peripheral
- Advertisement
- Manage services/characteristics
- Notifications/Indications
- HAL
- UART
- TWI
- SPI
- ADC
- Flash
- GPIO
- I2S

View File

@ -0,0 +1,3 @@
# Dynasteam D52Q dev board
(insert picture)

View File

@ -0,0 +1,5 @@
D52Q_SRC_C += \
d52q_board.c
OBJ += $(addprefix ${BUILD}/boards/D52Q/, $(D52Q_SRC_C:.c=.o))

View File

@ -0,0 +1,7 @@
#include "nrf52_board.h"
void
nrf52_board_init(void)
{
}

View File

@ -0,0 +1,9 @@
#pragma once
#include "nrf_sdm.h"
// Low frequency clock source to be used by the SoftDevice
#define NRF_CLOCK_LFCLKSRC {.source = NRF_CLOCK_LF_SRC_XTAL, \
.rc_ctiv = 0, \
.rc_temp_ctiv = 0, \
.xtal_accuracy = NRF_CLOCK_LF_XTAL_ACCURACY_20_PPM}

View File

@ -0,0 +1,3 @@
# Nordic nRF52 DK
[Link](https://www.nordicsemi.com/eng/Products/Bluetooth-low-energy/nRF52-DK)

View File

@ -0,0 +1,7 @@
PCA10040_SRC_C += \
pca10040_board.c
OBJ += $(addprefix ${BUILD}/boards/PCA10040/, $(PCA10040_SRC_C:.c=.o))
DEFINES += BOARD_PCA10040

View File

@ -0,0 +1,9 @@
#pragma once
#include "nrf_sdm.h"
// Low frequency clock source to be used by the SoftDevice
#define NRF_CLOCK_LFCLKSRC {.source = NRF_CLOCK_LF_SRC_XTAL, \
.rc_ctiv = 0, \
.rc_temp_ctiv = 0, \
.xtal_accuracy = NRF_CLOCK_LF_XTAL_ACCURACY_20_PPM}

View File

@ -0,0 +1,7 @@
#include "nrf52_board.h"
void
nrf52_board_init(void)
{
}

23
nrf52/gcc_nrf52_s132.ld Normal file
View File

@ -0,0 +1,23 @@
/* Linker script to configure memory regions. */
SEARCH_DIR(.)
GROUP(-lgcc -lc -lnosys)
MEMORY
{
FLASH (rx) : ORIGIN = 0x1c000, LENGTH = 0x64000
RAM (rwx) : ORIGIN = 0x20002080, LENGTH = 0xdf80
}
SECTIONS
{
.fs_data :
{
PROVIDE(__start_fs_data = .);
KEEP(*(.fs_data))
PROVIDE(__stop_fs_data = .);
} > RAM
} INSERT AFTER .data;
/* found in the nordic SDK components/toolchain/gcc */
INCLUDE "nrf5x_common.ld"

59
nrf52/main.c Normal file
View File

@ -0,0 +1,59 @@
#include "py/nlr.h"
#include "py/compile.h"
#include "py/runtime.h"
#include "py/repl.h"
#include "py/gc.h"
#include "lib/utils/pyexec.h"
#include "nrf52_board.h"
#include "nrf52_ble.h"
static char *stack_top;
static char heap[4 * 1024];
void nrf52_board_init(void);
void
gc_collect(void)
{
// WARNING: This gc_collect implementation doesn't try to get root
// pointers from CPU registers, and thus may function incorrectly.
void *dummy;
gc_collect_start();
gc_collect_root(&dummy, ((mp_uint_t)stack_top - (mp_uint_t)&dummy) / sizeof(mp_uint_t));
gc_collect_end();
gc_dump_info();
}
int
main(int argc, char **argv)
{
int stack_dummy;
stack_top = (char*)&stack_dummy;
#if MICROPY_ENABLE_GC
gc_init(heap, heap + sizeof(heap));
#endif
nrf52_board_init();
nrf52_ble_init();
mp_init();
#if MICROPY_REPL_EVENT_DRIVEN
pyexec_event_repl_init();
for (;;) {
int c = mp_hal_stdin_rx_chr();
if (pyexec_event_repl_process_char(c)) {
break;
}
}
#else
pyexec_friendly_repl();
#endif
mp_deinit();
NVIC_SystemReset();
return 0;
}

4
nrf52/mods/build.mk Normal file
View File

@ -0,0 +1,4 @@
MODS_SRC_C += \
builtin.c
OBJ += $(addprefix ${BUILD}/mods/, $(MODS_SRC_C:.c=.o))

54
nrf52/mods/builtin.c Normal file
View File

@ -0,0 +1,54 @@
/*
* This file is part of the Micro Python project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013, 2014 Damien P. George
* Copyright (c) 2015 Daniel Campora
* Copyright (c) 2016 Daniel Tralamazza
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include <stdio.h>
#include "lib/utils/pyhelp.h"
#include "py/runtime.h"
#include "extmod/vfs_fat_file.h"
#include "py/mphal.h"
// MP_DEFINE_CONST_FUN_OBJ_KW(mp_builtin_open_obj, 1, fatfs_builtin_open);
STATIC const char help_text[] = "Welcome to MicroPython!\n"
"For online help please visit http://micropython.org/help/.\n"
"For further help on a specific object, type help(obj)\n";
STATIC mp_obj_t pyb_help(uint n_args, const mp_obj_t *args) {
if (n_args == 0) {
// print a general help message
mp_hal_stdout_tx_str(help_text);
}
else {
// try to print something sensible about the given object
pyhelp_print_obj(args[0]);
}
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(mp_builtin_help_obj, 0, 1, pyb_help);

21
nrf52/mp_functions.c Normal file
View File

@ -0,0 +1,21 @@
// NOTE: the objective is to move these functions to their respective final implementations
#include "py/obj.h"
#include "py/lexer.h"
void nlr_jump_fail(void *val) {
}
mp_import_stat_t mp_import_stat(const char *path) {
return MP_IMPORT_STAT_NO_EXIST;
}
mp_lexer_t *mp_lexer_new_from_file(const char *filename) {
return NULL;
}
mp_obj_t mp_builtin_open(uint n_args, const mp_obj_t *args, mp_map_t *kwargs) {
return mp_const_none;
}
MP_DEFINE_CONST_FUN_OBJ_KW(mp_builtin_open_obj, 1, mp_builtin_open);

96
nrf52/mpconfigport.h Normal file
View File

@ -0,0 +1,96 @@
#include <stdint.h>
// options to control how Micro Python is built
#define MICROPY_QSTR_BYTES_IN_HASH (1)
// #define MICROPY_QSTR_EXTRA_POOL mp_qstr_frozen_const_pool
#define MICROPY_ALLOC_PATH_MAX (256)
#define MICROPY_ALLOC_PARSE_CHUNK_INIT (16)
#define MICROPY_EMIT_X64 (0)
#define MICROPY_EMIT_THUMB (0)
#define MICROPY_EMIT_INLINE_THUMB (0)
#define MICROPY_COMP_MODULE_CONST (0)
#define MICROPY_COMP_CONST (0)
#define MICROPY_COMP_DOUBLE_TUPLE_ASSIGN (0)
#define MICROPY_COMP_TRIPLE_TUPLE_ASSIGN (0)
#define MICROPY_MEM_STATS (0)
#define MICROPY_DEBUG_PRINTERS (0)
#define MICROPY_ENABLE_GC (1)
#define MICROPY_REPL_EVENT_DRIVEN (0)
#define MICROPY_HELPER_REPL (1)
#define MICROPY_HELPER_LEXER_UNIX (0)
#define MICROPY_ENABLE_SOURCE_LINE (0)
#define MICROPY_ENABLE_DOC_STRING (0)
#define MICROPY_ERROR_REPORTING (MICROPY_ERROR_REPORTING_TERSE)
#define MICROPY_BUILTIN_METHOD_CHECK_SELF_ARG (0)
#define MICROPY_PY_ASYNC_AWAIT (0)
#define MICROPY_PY_BUILTINS_BYTEARRAY (0)
#define MICROPY_PY_BUILTINS_MEMORYVIEW (0)
#define MICROPY_PY_BUILTINS_ENUMERATE (0)
#define MICROPY_PY_BUILTINS_FILTER (0)
#define MICROPY_PY_BUILTINS_FROZENSET (0)
#define MICROPY_PY_BUILTINS_REVERSED (0)
#define MICROPY_PY_BUILTINS_SET (0)
#define MICROPY_PY_BUILTINS_SLICE (0)
#define MICROPY_PY_BUILTINS_PROPERTY (0)
#define MICROPY_PY_BUILTINS_MIN_MAX (0)
#define MICROPY_PY___FILE__ (0)
#define MICROPY_PY_GC (0)
#define MICROPY_PY_ARRAY (0)
#define MICROPY_PY_ATTRTUPLE (0)
#define MICROPY_PY_COLLECTIONS (0)
#define MICROPY_PY_MATH (0)
#define MICROPY_PY_CMATH (0)
#define MICROPY_PY_IO (0)
#define MICROPY_PY_STRUCT (0)
#define MICROPY_PY_SYS (0)
#define MICROPY_MODULE_FROZEN_MPY (0)
#define MICROPY_CPYTHON_COMPAT (0)
#define MICROPY_LONGINT_IMPL (MICROPY_LONGINT_IMPL_NONE)
#define MICROPY_FLOAT_IMPL (MICROPY_FLOAT_IMPL_NONE)
// type definitions for the specific machine
#define BYTES_PER_WORD (4)
#define MICROPY_MAKE_POINTER_CALLABLE(p) ((void*)((mp_uint_t)(p) | 1))
// This port is intended to be 32-bit, but unfortunately, int32_t for
// different targets may be defined in different ways - either as int
// or as long. This requires different printf formatting specifiers
// to print such value. So, we avoid int32_t and use int directly.
#define UINT_FMT "%u"
#define INT_FMT "%d"
typedef int mp_int_t; // must be pointer size
typedef unsigned mp_uint_t; // must be pointer size
typedef void *machine_ptr_t; // must be of pointer size
typedef const void *machine_const_ptr_t; // must be of pointer size
typedef long mp_off_t;
#define MP_PLAT_PRINT_STRN(str, len) mp_hal_stdout_tx_strn_cooked(str, len)
// extra built in names to add to the global namespace
extern const struct _mp_obj_fun_builtin_t mp_builtin_open_obj;
#define MICROPY_PORT_BUILTINS \
{ MP_OBJ_NEW_QSTR(MP_QSTR_open), (mp_obj_t)&mp_builtin_open_obj },
// We need to provide a declaration/definition of alloca()
#include <alloca.h>
#define MICROPY_HW_BOARD_NAME "minimal"
#define MICROPY_HW_MCU_NAME "NRF52832"
#ifdef __linux__
#define MICROPY_MIN_USE_STDOUT (1)
#endif
#ifdef __thumb__
#define MICROPY_MIN_USE_CORTEX_CPU (1)
#define MICROPY_MIN_USE_STM32_MCU (1)
#endif
#define MP_STATE_PORT MP_STATE_VM
#define MICROPY_PORT_ROOT_POINTERS \
const char *readline_hist[8];

2
nrf52/mphalport.h Normal file
View File

@ -0,0 +1,2 @@
static inline mp_uint_t mp_hal_ticks_ms(void) { return 0; }
static inline void mp_hal_set_interrupt_char(char c) {}

7
nrf52/nordic/.gitignore vendored Normal file
View File

@ -0,0 +1,7 @@
# Ignore everything in this directory
*
# Except
!.gitignore
!build.mk
!gcc_startup_nrf52.S

105
nrf52/nordic/build.mk Normal file
View File

@ -0,0 +1,105 @@
# this file's folder
SDK_DIR := $(abspath $(dir $(lastword ${MAKEFILE_LIST})))
# -D<define> in CFLAGS
DEFINES += __HEAP_SIZE=0
DEFINES += BLE_STACK_SUPPORT_REQD
DEFINES += CONFIG_GPIO_AS_PINRESET
DEFINES += NRF52
DEFINES += NRF52_PAN_12
DEFINES += NRF52_PAN_15
DEFINES += NRF52_PAN_20
DEFINES += NRF52_PAN_30
DEFINES += NRF52_PAN_31
DEFINES += NRF52_PAN_36
DEFINES += NRF52_PAN_51
DEFINES += NRF52_PAN_53
DEFINES += NRF52_PAN_54
DEFINES += NRF52_PAN_55
DEFINES += NRF52_PAN_58
DEFINES += NRF52_PAN_62
DEFINES += NRF52_PAN_63
DEFINES += NRF52_PAN_64
DEFINES += S132
DEFINES += SOFTDEVICE_PRESENT
DEFINES += SWI_DISABLE0
# nordic SDK C sources (relative path)
SDK_SRC_C += \
components/ble/ble_advertising/ble_advertising.c \
components/ble/ble_services/ble_nus/ble_nus.c \
components/ble/common/ble_advdata.c \
components/ble/common/ble_conn_params.c \
components/ble/common/ble_conn_state.c \
components/ble/common/ble_srv_common.c \
components/ble/peer_manager/gatt_cache_manager.c \
components/ble/peer_manager/gattc_cache_manager.c \
components/ble/peer_manager/gatts_cache_manager.c \
components/ble/peer_manager/id_manager.c \
components/ble/peer_manager/peer_data.c \
components/ble/peer_manager/peer_data_storage.c \
components/ble/peer_manager/peer_database.c \
components/ble/peer_manager/peer_id.c \
components/ble/peer_manager/peer_manager.c \
components/ble/peer_manager/pm_buffer.c \
components/ble/peer_manager/pm_mutex.c \
components/ble/peer_manager/security_dispatcher.c \
components/ble/peer_manager/security_manager.c \
components/drivers_nrf/delay/nrf_delay.c \
components/drivers_nrf/pstorage/pstorage.c \
components/libraries/fds/fds.c \
components/libraries/fifo/app_fifo.c \
components/libraries/fstorage/fstorage.c \
components/libraries/timer/app_timer.c \
components/libraries/util/app_util_platform.c \
components/libraries/util/sdk_mapped_flags.c \
components/softdevice/common/softdevice_handler/softdevice_handler.c \
components/toolchain/system_nrf52.c
# add segger RTT
ifeq (${BTYPE}, debug)
DEFINES += USE_RTT
SDK_SRC_C += \
external/segger_rtt/RTT_Syscalls_GCC.c \
external/segger_rtt/SEGGER_RTT.c \
external/segger_rtt/SEGGER_RTT_printf.c
endif
# # nordic SDK ASM sources (relative path)
# SDK_SRC_ASM += \
# components/toolchain/gcc/gcc_startup_nrf52.s
# include source folders (sort removes duplicates)
SDK_INC_DIRS += $(sort $(dir ${SDK_SRC_C}))
# ble.h
SDK_INC_DIRS += components/softdevice/s132/headers
# nrf52.h compiler_abstraction.h
SDK_INC_DIRS += components/device
# core_cm4.h
SDK_INC_DIRS += components/toolchain/CMSIS/Include
# section_vars.h
SDK_INC_DIRS += components/libraries/experimental_section_vars
# fstorage_config.h
SDK_INC_DIRS += components/libraries/fstorage/config
# nrf_drv_config.h
SDK_INC_DIRS += components/drivers_nrf/config
# app_util.h
SDK_INC_DIRS += components/libraries/util
# fds_config.h
SDK_INC_DIRS += components/libraries/fds/config
# include full path
INC += $(patsubst %,-I${SDK_DIR}/%, ${SDK_INC_DIRS})
# object folder
NORDIC_BUILD = ${BUILD}/nordic
OBJ += $(addprefix ${NORDIC_BUILD}/, $(SDK_SRC_C:.c=.o))
# OBJ += $(addprefix ${NORDIC_BUILD}/, $(SDK_SRC_ASM:.s=.o))
OBJ += ${NORDIC_BUILD}/gcc_startup_nrf52.o
# linker script folder
LDFLAGS += -L${SDK_DIR}/components/toolchain/gcc
# softdevice .hex file
SOFTDEV_HEX ?= $(lastword $(wildcard nordic/components/softdevice/s132/hex/s132*softdevice.hex))

View File

@ -0,0 +1,524 @@
/* Copyright (c) 2013 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- 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.
- Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
---------------------------------------------------------------------------*/
.syntax unified
.arch armv7e-m
.section .stack
.align 3
#ifdef __STACK_SIZE
.equ Stack_Size, __STACK_SIZE
#else
.equ Stack_Size, 8192
#endif
.globl __StackTop
.globl __StackLimit
__StackLimit:
.space Stack_Size
.size __StackLimit, . - __StackLimit
__StackTop:
.size __StackTop, . - __StackTop
.section .heap
.align 3
#ifdef __HEAP_SIZE
.equ Heap_Size, __HEAP_SIZE
#else
.equ Heap_Size, 8192
#endif
.globl __HeapBase
.globl __HeapLimit
__HeapBase:
.if Heap_Size
.space Heap_Size
.endif
.size __HeapBase, . - __HeapBase
__HeapLimit:
.size __HeapLimit, . - __HeapLimit
.section .isr_vector
.align 2
.globl __isr_vector
__isr_vector:
.long __StackTop /* Top of Stack */
.long Reset_Handler
.long NMI_Handler
.long HardFault_Handler
.long MemoryManagement_Handler
.long BusFault_Handler
.long UsageFault_Handler
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long SVC_Handler
.long DebugMonitor_Handler
.long 0 /*Reserved */
.long PendSV_Handler
.long SysTick_Handler
/* External Interrupts */
.long POWER_CLOCK_IRQHandler
.long RADIO_IRQHandler
.long UARTE0_UART0_IRQHandler
.long SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQHandler
.long SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQHandler
.long NFCT_IRQHandler
.long GPIOTE_IRQHandler
.long SAADC_IRQHandler
.long TIMER0_IRQHandler
.long TIMER1_IRQHandler
.long TIMER2_IRQHandler
.long RTC0_IRQHandler
.long TEMP_IRQHandler
.long RNG_IRQHandler
.long ECB_IRQHandler
.long CCM_AAR_IRQHandler
.long WDT_IRQHandler
.long RTC1_IRQHandler
.long QDEC_IRQHandler
.long COMP_LPCOMP_IRQHandler
.long SWI0_EGU0_IRQHandler
.long SWI1_EGU1_IRQHandler
.long SWI2_EGU2_IRQHandler
.long SWI3_EGU3_IRQHandler
.long SWI4_EGU4_IRQHandler
.long SWI5_EGU5_IRQHandler
.long TIMER3_IRQHandler
.long TIMER4_IRQHandler
.long PWM0_IRQHandler
.long PDM_IRQHandler
.long 0 /*Reserved */
.long 0 /*Reserved */
.long MWU_IRQHandler
.long PWM1_IRQHandler
.long PWM2_IRQHandler
.long SPIM2_SPIS2_SPI2_IRQHandler
.long RTC2_IRQHandler
.long I2S_IRQHandler
.long FPU_IRQHandler
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.long 0 /*Reserved */
.size __isr_vector, . - __isr_vector
/* Reset Handler */
.text
.thumb
.thumb_func
.align 1
.globl Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
/* Loop to copy data from read only memory to RAM.
* The ranges of copy from/to are specified by following symbols:
* __etext: LMA of start of the section to copy from. Usually end of text
* __data_start__: VMA of start of the section to copy to.
* __bss_start__: VMA of end of the section to copy to. Normally __data_end__ is used, but by using __bss_start__
* the user can add their own initialized data section before BSS section with the INTERT AFTER command.
*
* All addresses must be aligned to 4 bytes boundary.
*/
ldr r1, =__etext
ldr r2, =__data_start__
ldr r3, =__bss_start__
subs r3, r2
ble .L_loop1_done
.L_loop1:
subs r3, #4
ldr r0, [r1,r3]
str r0, [r2,r3]
bgt .L_loop1
.L_loop1_done:
/* This part of work usually is done in C library startup code. Otherwise,
* define __STARTUP_CLEAR_BSS to enable it in this startup. This section
* clears the RAM where BSS data is located.
*
* The BSS section is specified by following symbols
* __bss_start__: start of the BSS section.
* __bss_end__: end of the BSS section.
*
* All addresses must be aligned to 4 bytes boundary.
*/
#ifdef __STARTUP_CLEAR_BSS
ldr r1, =__bss_start__
ldr r2, =__bss_end__
movs r0, 0
subs r2, r1
ble .L_loop3_done
.L_loop3:
subs r2, #4
str r0, [r1, r2]
bgt .L_loop3
.L_loop3_done:
#endif /* __STARTUP_CLEAR_BSS */
/* Execute SystemInit function. */
bl SystemInit
/* Call _start function provided by libraries.
* If those libraries are not accessible, define __START as your entry point.
*/
#ifndef __START
#define __START _start
#endif
bl __START
.pool
.size Reset_Handler,.-Reset_Handler
.section ".text"
/* Dummy Exception Handlers (infinite loops which can be modified) */
.weak NMI_Handler
.type NMI_Handler, %function
NMI_Handler:
b .
.size NMI_Handler, . - NMI_Handler
.weak HardFault_Handler
.type HardFault_Handler, %function
HardFault_Handler:
b .
.size HardFault_Handler, . - HardFault_Handler
.weak MemoryManagement_Handler
.type MemoryManagement_Handler, %function
MemoryManagement_Handler:
b .
.size MemoryManagement_Handler, . - MemoryManagement_Handler
.weak BusFault_Handler
.type BusFault_Handler, %function
BusFault_Handler:
b .
.size BusFault_Handler, . - BusFault_Handler
.weak UsageFault_Handler
.type UsageFault_Handler, %function
UsageFault_Handler:
b .
.size UsageFault_Handler, . - UsageFault_Handler
.weak SVC_Handler
.type SVC_Handler, %function
SVC_Handler:
b .
.size SVC_Handler, . - SVC_Handler
.weak DebugMonitor_Handler
.type DebugMonitor_Handler, %function
DebugMonitor_Handler:
b .
.size DebugMonitor_Handler, . - DebugMonitor_Handler
.weak PendSV_Handler
.type PendSV_Handler, %function
PendSV_Handler:
b .
.size PendSV_Handler, . - PendSV_Handler
.weak SysTick_Handler
.type SysTick_Handler, %function
SysTick_Handler:
b .
.size SysTick_Handler, . - SysTick_Handler
/* IRQ Handlers */
.globl Default_Handler
.type Default_Handler, %function
Default_Handler:
b .
.size Default_Handler, . - Default_Handler
.macro IRQ handler
.weak \handler
.set \handler, Default_Handler
.endm
IRQ POWER_CLOCK_IRQHandler
IRQ RADIO_IRQHandler
IRQ UARTE0_UART0_IRQHandler
IRQ SPIM0_SPIS0_TWIM0_TWIS0_SPI0_TWI0_IRQHandler
IRQ SPIM1_SPIS1_TWIM1_TWIS1_SPI1_TWI1_IRQHandler
IRQ NFCT_IRQHandler
IRQ GPIOTE_IRQHandler
IRQ SAADC_IRQHandler
IRQ TIMER0_IRQHandler
IRQ TIMER1_IRQHandler
IRQ TIMER2_IRQHandler
IRQ RTC0_IRQHandler
IRQ TEMP_IRQHandler
IRQ RNG_IRQHandler
IRQ ECB_IRQHandler
IRQ CCM_AAR_IRQHandler
IRQ WDT_IRQHandler
IRQ RTC1_IRQHandler
IRQ QDEC_IRQHandler
IRQ COMP_LPCOMP_IRQHandler
IRQ SWI0_EGU0_IRQHandler
IRQ SWI1_EGU1_IRQHandler
IRQ SWI2_EGU2_IRQHandler
IRQ SWI3_EGU3_IRQHandler
IRQ SWI4_EGU4_IRQHandler
IRQ SWI5_EGU5_IRQHandler
IRQ TIMER3_IRQHandler
IRQ TIMER4_IRQHandler
IRQ PWM0_IRQHandler
IRQ PDM_IRQHandler
IRQ MWU_IRQHandler
IRQ PWM1_IRQHandler
IRQ PWM2_IRQHandler
IRQ SPIM2_SPIS2_SPI2_IRQHandler
IRQ RTC2_IRQHandler
IRQ I2S_IRQHandler
IRQ FPU_IRQHandler
.end

19
nrf52/nrf52_app_error.c Normal file
View File

@ -0,0 +1,19 @@
#include <stdint.h>
#include "app_error.h"
void
#ifdef DEBUG
app_error_handler(ret_code_t error_code, uint32_t line_num, const uint8_t * p_file_name)
#else
app_error_handler_bare(ret_code_t error_code)
#endif
{
#ifdef DEBUG
for (;;) {
/* FOREVER */
}
#else
NVIC_SystemReset();
#endif
}

481
nrf52/nrf52_ble.c Normal file
View File

@ -0,0 +1,481 @@
#include "nrf52_ble.h"
#include "nrf52_board.h"
#include "app_error.h"
#include "app_fifo.h"
#include "app_timer.h"
#include "ble_advertising.h"
#include "ble_conn_params.h"
#include "ble_conn_state.h"
#include "ble_hci.h"
#include "ble_nus.h"
#include "ble_srv_common.h"
#include "fds.h"
#include "fds.h"
#include "fstorage.h"
#include "peer_manager.h"
#include "softdevice_handler.h"
#define CENTRAL_LINK_COUNT 0 /**< Number of central links used by the application. When changing this number remember to adjust the RAM settings*/
#define PERIPHERAL_LINK_COUNT 1 /**< Number of peripheral links used by the application. When changing this number remember to adjust the RAM settings*/
#define DEVICE_NAME "micropython"
#define MIN_CONN_INTERVAL MSEC_TO_UNITS(20, UNIT_1_25_MS) /**< Minimum acceptable connection interval (0.02 seconds). */
#define MAX_CONN_INTERVAL MSEC_TO_UNITS(200, UNIT_1_25_MS) /**< Maximum acceptable connection interval (0.2 second). */
#define SLAVE_LATENCY 0 /**< Slave latency. */
#define CONN_SUP_TIMEOUT MSEC_TO_UNITS(3000, UNIT_10_MS) /**< Connection supervisory timeout (3 seconds). */
#define APP_ADV_INTERVAL MSEC_TO_UNITS(25, UNIT_0_625_MS)
#define APP_ADV_TIMEOUT_IN_SECONDS 180
#define APP_TIMER_PRESCALER 0 /**< Value of the RTC1 PRESCALER register. */
#define APP_TIMER_OP_QUEUE_SIZE 4 /**< Size of timer operation queues. */
#define FIRST_CONN_PARAMS_UPDATE_DELAY APP_TIMER_TICKS(5000, APP_TIMER_PRESCALER) /**< Time from initiating event (connect or start of notification) to first time sd_ble_gap_conn_param_update is called (5 seconds). */
#define NEXT_CONN_PARAMS_UPDATE_DELAY APP_TIMER_TICKS(30000, APP_TIMER_PRESCALER) /**< Time between each call to sd_ble_gap_conn_param_update after the first call (30 seconds). */
#define MAX_CONN_PARAMS_UPDATE_COUNT 3
#define SEC_PARAM_BOND 1 /**< Perform bonding. */
#define SEC_PARAM_MITM 0 /**< Man In The Middle protection not required. */
#define SEC_PARAM_LESC 0 /**< LE Secure Connections not enabled. */
#define SEC_PARAM_KEYPRESS 0 /**< Keypress notifications not enabled. */
#define SEC_PARAM_IO_CAPABILITIES BLE_GAP_IO_CAPS_NONE /**< No I/O capabilities. */
#define SEC_PARAM_OOB 0 /**< Out Of Band data not available. */
#define SEC_PARAM_MIN_KEY_SIZE 7 /**< Minimum encryption key size. */
#define SEC_PARAM_MAX_KEY_SIZE 16 /**< Maximum encryption key size. */
#define NUS_RX_FIFO_BUFFER_SIZE 64
static ble_uuid_t m_adv_uuids[] = {{BLE_UUID_NUS_SERVICE, 0}}; /**< Universally unique service identifiers. */
static ble_nus_t m_nus;
static app_fifo_t m_nus_rx_fifo;
static uint8_t m_nus_rx_fifo_buffer[NUS_RX_FIFO_BUFFER_SIZE];
static void
ble_evt_dispatch(ble_evt_t * p_ble_evt)
{
ble_conn_state_on_ble_evt(p_ble_evt);
pm_on_ble_evt(p_ble_evt);
ble_conn_params_on_ble_evt(p_ble_evt);
ble_advertising_on_ble_evt(p_ble_evt);
ble_nus_on_ble_evt(&m_nus, p_ble_evt);
}
static void
sys_evt_dispatch(uint32_t sys_evt)
{
fs_sys_event_handler(sys_evt);
ble_advertising_on_sys_evt(sys_evt);
}
static void
ble_stack_init(void)
{
nrf_clock_lf_cfg_t clock_lf_cfg = NRF_CLOCK_LFCLKSRC;
// Initialize the SoftDevice handler module.
SOFTDEVICE_HANDLER_INIT(&clock_lf_cfg, NULL);
ble_enable_params_t ble_enable_params;
uint32_t err_code = softdevice_enable_get_default_config(CENTRAL_LINK_COUNT,
PERIPHERAL_LINK_COUNT,
&ble_enable_params);
APP_ERROR_CHECK(err_code);
//Check the ram settings against the used number of links
CHECK_RAM_START_ADDR(CENTRAL_LINK_COUNT, PERIPHERAL_LINK_COUNT);
// Enable BLE stack.
err_code = softdevice_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);
// Register with the SoftDevice handler module for BLE events.
err_code = softdevice_sys_evt_handler_set(sys_evt_dispatch);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for the GAP initialization.
*
* @details This function sets up all the necessary GAP (Generic Access Profile) parameters of the
* device including the device name, appearance, and the preferred connection parameters.
*/
static void
gap_params_init(void)
{
uint32_t err_code;
ble_gap_conn_params_t gap_conn_params;
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 *)DEVICE_NAME,
strlen(DEVICE_NAME));
APP_ERROR_CHECK(err_code);
err_code = sd_ble_gap_appearance_set(BLE_APPEARANCE_UNKNOWN);
APP_ERROR_CHECK(err_code);
memset(&gap_conn_params, 0, sizeof(gap_conn_params));
gap_conn_params.min_conn_interval = MIN_CONN_INTERVAL;
gap_conn_params.max_conn_interval = MAX_CONN_INTERVAL;
gap_conn_params.slave_latency = SLAVE_LATENCY;
gap_conn_params.conn_sup_timeout = CONN_SUP_TIMEOUT;
err_code = sd_ble_gap_ppcp_set(&gap_conn_params);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling advertising events.
*
* @details This function will be called for advertising events which are passed to the application.
*
* @param[in] ble_adv_evt Advertising event.
*/
static void
on_adv_evt(ble_adv_evt_t ble_adv_evt)
{
switch (ble_adv_evt)
{
case BLE_ADV_EVT_FAST:
break;
case BLE_ADV_EVT_IDLE:
break;
default:
break;
}
}
/**@brief Function for initializing the Advertising functionality.
*/
static void
advertising_init(void)
{
uint32_t err_code;
ble_advdata_t advdata;
// Build advertising data struct to pass into @ref ble_advertising_init.
memset(&advdata, 0, sizeof(advdata));
advdata.name_type = BLE_ADVDATA_FULL_NAME;
advdata.include_appearance = true;
advdata.flags = BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE;
advdata.uuids_complete.uuid_cnt = sizeof(m_adv_uuids) / sizeof(m_adv_uuids[0]);
advdata.uuids_complete.p_uuids = m_adv_uuids;
ble_adv_modes_config_t options = {0};
options.ble_adv_fast_enabled = BLE_ADV_FAST_ENABLED;
options.ble_adv_fast_interval = APP_ADV_INTERVAL;
options.ble_adv_fast_timeout = APP_ADV_TIMEOUT_IN_SECONDS;
err_code = ble_advertising_init(&advdata, NULL, &options, on_adv_evt, NULL);
APP_ERROR_CHECK(err_code);
}
static void
nus_data_handler(ble_nus_t * p_nus, uint8_t * p_data, uint16_t length)
{
for (uint32_t i = 0; i < length; i++) {
// XXX
app_fifo_put(&m_nus_rx_fifo, p_data[i]);
}
}
static void
services_init(void)
{
uint32_t err_code;
ble_nus_init_t nus_init = {0};
nus_init.data_handler = nus_data_handler;
err_code = ble_nus_init(&m_nus, &nus_init);
APP_ERROR_CHECK(err_code);
m_adv_uuids[0].type = m_nus.uuid_type;
err_code = app_fifo_init(&m_nus_rx_fifo, m_nus_rx_fifo_buffer, NUS_RX_FIFO_BUFFER_SIZE);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling a Connection Parameters error.
*
* @param[in] nrf_error Error code containing information about what went wrong.
*/
static void conn_params_error_handler(uint32_t nrf_error)
{
APP_ERROR_HANDLER(nrf_error);
}
/**@brief Function for initializing the Connection Parameters module.
*/
static void
conn_params_init(void)
{
uint32_t err_code;
ble_conn_params_init_t cp_init;
memset(&cp_init, 0, sizeof(cp_init));
cp_init.p_conn_params = NULL;
cp_init.first_conn_params_update_delay = FIRST_CONN_PARAMS_UPDATE_DELAY;
cp_init.next_conn_params_update_delay = NEXT_CONN_PARAMS_UPDATE_DELAY;
cp_init.max_conn_params_update_count = MAX_CONN_PARAMS_UPDATE_COUNT;
cp_init.start_on_notify_cccd_handle = BLE_GATT_HANDLE_INVALID;
cp_init.disconnect_on_fail = true;
cp_init.evt_handler = NULL;
cp_init.error_handler = conn_params_error_handler;
err_code = ble_conn_params_init(&cp_init);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for starting advertising.
*/
static void
advertising_start(void)
{
uint32_t err_code = ble_advertising_start(BLE_ADV_MODE_FAST);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling Peer Manager events.
*
* @param[in] p_evt Peer Manager event.
*/
static void
pm_evt_handler(pm_evt_t const * p_evt)
{
ret_code_t err_code;
switch(p_evt->evt_id)
{
case PM_EVT_BONDED_PEER_CONNECTED:
err_code = pm_peer_rank_highest(p_evt->peer_id);
if (err_code != NRF_ERROR_BUSY)
{
APP_ERROR_CHECK(err_code);
}
break;//PM_EVT_BONDED_PEER_CONNECTED
case PM_EVT_CONN_SEC_START:
break;//PM_EVT_CONN_SEC_START
case PM_EVT_CONN_SEC_SUCCEEDED:
{
NRF_LOG_PRINTF_DEBUG("Link secured. Role: %d. conn_handle: %d, Procedure: %d\r\n",
ble_conn_state_role(p_evt->conn_handle),
p_evt->conn_handle,
p_evt->params.conn_sec_succeeded.procedure);
err_code = pm_peer_rank_highest(p_evt->peer_id);
if (err_code != NRF_ERROR_BUSY)
{
APP_ERROR_CHECK(err_code);
}
}
break;//PM_EVT_CONN_SEC_SUCCEEDED
case PM_EVT_CONN_SEC_FAILED:
{
/** In some cases, when securing fails, it can be restarted directly. Sometimes it can
* be restarted, but only after changing some Security Parameters. Sometimes, it cannot
* be restarted until the link is disconnected and reconnected. Sometimes it is
* impossible, to secure the link, or the peer device does not support it. How to
* handle this error is highly application dependent. */
switch (p_evt->params.conn_sec_failed.error)
{
case PM_CONN_SEC_ERROR_PIN_OR_KEY_MISSING:
// Rebond if one party has lost its keys.
err_code = pm_conn_secure(p_evt->conn_handle, true);
if (err_code != NRF_ERROR_INVALID_STATE)
{
APP_ERROR_CHECK(err_code);
}
break;//PM_CONN_SEC_ERROR_PIN_OR_KEY_MISSING
default:
break;
}
}
break;//PM_EVT_CONN_SEC_FAILED
case PM_EVT_CONN_SEC_CONFIG_REQ:
{
// Reject pairing request from an already bonded peer.
pm_conn_sec_config_t conn_sec_config = {.allow_repairing = false};
pm_conn_sec_config_reply(p_evt->conn_handle, &conn_sec_config);
}
break;//PM_EVT_CONN_SEC_CONFIG_REQ
case PM_EVT_STORAGE_FULL:
{
// Run garbage collection on the flash.
err_code = fds_gc();
if (err_code == FDS_ERR_BUSY || err_code == FDS_ERR_NO_SPACE_IN_QUEUES)
{
// Retry.
}
else
{
APP_ERROR_CHECK(err_code);
}
}
break;//PM_EVT_STORAGE_FULL
case PM_EVT_ERROR_UNEXPECTED:
// Assert.
APP_ERROR_CHECK(p_evt->params.error_unexpected.error);
break;//PM_EVT_ERROR_UNEXPECTED
case PM_EVT_PEER_DATA_UPDATE_SUCCEEDED:
break;//PM_EVT_PEER_DATA_UPDATE_SUCCEEDED
case PM_EVT_PEER_DATA_UPDATE_FAILED:
// Assert.
APP_ERROR_CHECK_BOOL(false);
break;//PM_EVT_PEER_DATA_UPDATE_FAILED
case PM_EVT_PEER_DELETE_SUCCEEDED:
break;//PM_EVT_PEER_DELETE_SUCCEEDED
case PM_EVT_PEER_DELETE_FAILED:
// Assert.
APP_ERROR_CHECK(p_evt->params.peer_delete_failed.error);
break;//PM_EVT_PEER_DELETE_FAILED
case PM_EVT_PEERS_DELETE_SUCCEEDED:
advertising_start();
break;//PM_EVT_PEERS_DELETE_SUCCEEDED
case PM_EVT_PEERS_DELETE_FAILED:
// Assert.
APP_ERROR_CHECK(p_evt->params.peers_delete_failed_evt.error);
break;//PM_EVT_PEERS_DELETE_FAILED
case PM_EVT_LOCAL_DB_CACHE_APPLIED:
break;//PM_EVT_LOCAL_DB_CACHE_APPLIED
case PM_EVT_LOCAL_DB_CACHE_APPLY_FAILED:
// The local database has likely changed, send service changed indications.
pm_local_database_has_changed();
break;//PM_EVT_LOCAL_DB_CACHE_APPLY_FAILED
case PM_EVT_SERVICE_CHANGED_IND_SENT:
break;//PM_EVT_SERVICE_CHANGED_IND_SENT
case PM_EVT_SERVICE_CHANGED_IND_CONFIRMED:
break;//PM_EVT_SERVICE_CHANGED_IND_CONFIRMED
default:
// No implementation needed.
break;
}
}
static void
peer_manager_init(bool erase_bonds)
{
ble_gap_sec_params_t sec_param;
ret_code_t err_code;
err_code = pm_init();
APP_ERROR_CHECK(err_code);
if (erase_bonds)
{
err_code = pm_peers_delete();
APP_ERROR_CHECK(err_code);
}
memset(&sec_param, 0, sizeof(ble_gap_sec_params_t));
// Security parameters to be used for all security procedures.
sec_param.bond = SEC_PARAM_BOND;
sec_param.mitm = SEC_PARAM_MITM;
sec_param.lesc = SEC_PARAM_LESC;
sec_param.keypress = SEC_PARAM_KEYPRESS;
sec_param.io_caps = SEC_PARAM_IO_CAPABILITIES;
sec_param.oob = SEC_PARAM_OOB;
sec_param.min_key_size = SEC_PARAM_MIN_KEY_SIZE;
sec_param.max_key_size = SEC_PARAM_MAX_KEY_SIZE;
sec_param.kdist_own.enc = 1;
sec_param.kdist_own.id = 1;
sec_param.kdist_peer.enc = 1;
sec_param.kdist_peer.id = 1;
err_code = pm_sec_params_set(&sec_param);
APP_ERROR_CHECK(err_code);
err_code = pm_register(pm_evt_handler);
APP_ERROR_CHECK(err_code);
}
static void
timers_init()
{
APP_TIMER_INIT(APP_TIMER_PRESCALER, APP_TIMER_OP_QUEUE_SIZE, false);
}
void
nrf52_ble_init(void)
{
timers_init();
ble_stack_init();
peer_manager_init(false);
gap_params_init();
services_init();
advertising_init();
conn_params_init();
advertising_start();
}
static void
power_manage()
{
uint32_t err_code = sd_app_evt_wait();
APP_ERROR_CHECK(err_code);
}
// ########################### MP IO functions ###########################
void
mp_hal_stdout_tx_strn(const char *str, size_t len)
{
uint32_t err_code;
uint8_t *buf = (uint8_t *)str;
size_t send_len;
while (len > 0) {
if (len >= BLE_NUS_MAX_DATA_LEN)
send_len = BLE_NUS_MAX_DATA_LEN;
else
send_len = len;
err_code = ble_nus_string_send(&m_nus, buf, send_len);
if (err_code == NRF_SUCCESS) {
len -= send_len;
buf += send_len;
} else if (err_code != NRF_ERROR_INVALID_STATE) {
APP_ERROR_CHECK(err_code);
}
}
}
int
mp_hal_stdin_rx_chr()
{
uint8_t byte;
for (;;) {
if (app_fifo_get(&m_nus_rx_fifo, &byte) == NRF_SUCCESS) {
return byte;
}
power_manage();
}
}

4
nrf52/nrf52_ble.h Normal file
View File

@ -0,0 +1,4 @@
#pragma once
void nrf52_ble_init(void);

72
nrf52/pstorage_platform.h Normal file
View File

@ -0,0 +1,72 @@
/* Copyright (c) 2013 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
/** @cond To make doxygen skip this file */
/** @file
* This header contains defines with respect persistent storage that are specific to
* persistent storage implementation and application use case.
*/
#ifndef PSTORAGE_PL_H__
#define PSTORAGE_PL_H__
#include <stdint.h>
#include "nrf.h"
static __INLINE uint16_t pstorage_flash_page_size()
{
return (uint16_t)NRF_FICR->CODEPAGESIZE;
}
#define PSTORAGE_FLASH_PAGE_SIZE pstorage_flash_page_size() /**< Size of one flash page. */
#define PSTORAGE_FLASH_EMPTY_MASK 0xFFFFFFFF /**< Bit mask that defines an empty address in flash. */
static __INLINE uint32_t pstorage_flash_page_end()
{
uint32_t bootloader_addr = NRF_UICR->NRFFW[0];
return ((bootloader_addr != PSTORAGE_FLASH_EMPTY_MASK) ?
(bootloader_addr/ PSTORAGE_FLASH_PAGE_SIZE) : NRF_FICR->CODESIZE);
}
#define PSTORAGE_FLASH_PAGE_END pstorage_flash_page_end()
#define PSTORAGE_NUM_OF_PAGES 1 /**< Number of flash pages allocated for the pstorage module excluding the swap page, configurable based on system requirements. */
#define PSTORAGE_MIN_BLOCK_SIZE 0x0010 /**< Minimum size of block that can be registered with the module. Should be configured based on system requirements, recommendation is not have this value to be at least size of word. */
#define PSTORAGE_DATA_START_ADDR ((PSTORAGE_FLASH_PAGE_END - PSTORAGE_NUM_OF_PAGES - 1) \
* PSTORAGE_FLASH_PAGE_SIZE) /**< Start address for persistent data, configurable according to system requirements. */
#define PSTORAGE_DATA_END_ADDR ((PSTORAGE_FLASH_PAGE_END - 1) * PSTORAGE_FLASH_PAGE_SIZE) /**< End address for persistent data, configurable according to system requirements. */
#define PSTORAGE_SWAP_ADDR PSTORAGE_DATA_END_ADDR /**< Top-most page is used as swap area for clear and update. */
#define PSTORAGE_MAX_BLOCK_SIZE PSTORAGE_FLASH_PAGE_SIZE /**< Maximum size of block that can be registered with the module. Should be configured based on system requirements. And should be greater than or equal to the minimum size. */
#define PSTORAGE_CMD_QUEUE_SIZE 10 /**< Maximum number of flash access commands that can be maintained by the module for all applications. Configurable. */
/** Abstracts persistently memory block identifier. */
typedef uint32_t pstorage_block_t;
typedef struct
{
uint32_t module_id; /**< Module ID.*/
pstorage_block_t block_id; /**< Block ID.*/
} pstorage_handle_t;
typedef uint16_t pstorage_size_t; /** Size of length and offset fields. */
/**@brief Handles Flash Access Result Events. To be called in the system event dispatcher of the application. */
void pstorage_sys_event_handler (uint32_t sys_evt);
#endif // PSTORAGE_PL_H__
/** @} */
/** @endcond */

0
nrf52/qstrdefsport.h Normal file
View File