提交 0f37b300 编写于 作者: X xieyangrun

update NRF52832 support NRF52SDK13

上级 3aa97964

要显示的变更太多。

To preserve performance only 1000 of 1000+ files are displayed.
import rtconfig
Import('RTT_ROOT')
from building import *
# get current directory
cwd = GetCurrentDir()
# The set of source files associated with this SConscript file.
src = Split("""
nrf52832/Source/templates/system_nrf52.c
""")
#add for Startup script
if rtconfig.CROSS_TOOL == 'gcc':
src = src + ['nrf52832/Source/templates/arm/gcc_startup_nrf52.s']
elif rtconfig.CROSS_TOOL == 'keil':
src = src + ['nrf52832/Source/templates/arm/arm_startup_nrf52.s']
elif rtconfig.CROSS_TOOL == 'iar':
src = src + ['nrf52832/Source/templates/arm/iar_startup_nrf52.s']
path = [cwd + '/CMSIS/Include',
cwd + '/nrf52832/Include']
CPPDEFINES = ['USE_STDPERIPH_DRIVER', 'NRF52']
group = DefineGroup('Startup Code', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
Return('group')
/* Copyright (c) 2015, Nordic Semiconductor ASA
* 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 Nordic Semiconductor ASA 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.
*
*/
#ifndef NRF_H
#define NRF_H
#if defined(_WIN32)
/* Do not include nrf51 specific files when building for PC host */
#elif defined(__unix)
/* Do not include nrf51 specific files when building for PC host */
#elif defined(__APPLE__)
/* Do not include nrf51 specific files when building for PC host */
#else
/* Family selection for family includes. */
#if defined (NRF51)
#include "nrf51.h"
#include "nrf51_bitfields.h"
#include "nrf51_deprecated.h"
#elif defined (NRF52)
#include "nrf52.h"
#include "nrf52_bitfields.h"
#include "nrf51_to_nrf52.h"
#else
#error "Device family must be defined. See nrf.h."
#endif /* NRF51, NRF52 */
#include "compiler_abstraction.h"
#endif /* _WIN32 || __unix || __APPLE__ */
#endif /* NRF_H */
/*
Copyright (c) 2015, Nordic Semiconductor ASA
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 Nordic Semiconductor ASA 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.
*/
/*
NOTE: Template files (including this one) are application specific and therefore
expected to be copied into the application project folder prior to its use!
*/
.syntax unified
.arch armv6-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 .Vectors
.align 2
.globl __Vectors
__Vectors:
.long __StackTop /* Top of Stack */
.long Reset_Handler /* Reset Handler */
.long NMI_Handler /* NMI Handler */
.long HardFault_Handler /* Hard Fault Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long SVC_Handler /* SVCall Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long PendSV_Handler /* PendSV Handler */
.long SysTick_Handler /* 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 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 */
.long 0 /*Reserved */
.size __Vectors, . - __Vectors
/* Reset Handler */
.text
.thumb
.thumb_func
.align 1
.globl Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
.fnstart
/* Loop to copy data from read only memory to RAM. The ranges
* of copy from/to are specified by following symbols evaluated in
* linker script.
* __etext: End of code section, i.e., begin of data sections to copy from.
* __data_start__/__data_end__: RAM address range that data should be
* copied to. Both must be aligned to 4 bytes boundary. */
ldr r1, =__etext
ldr r2, =__data_start__
ldr r3, =__data_end__
subs r3, r2
ble .LC0
.LC1:
subs r3, 4
ldr r0, [r1,r3]
str r0, [r2,r3]
bgt .LC1
.LC0:
LDR R0, =SystemInit
BLX R0
LDR R0, =_start
BX R0
.pool
.cantunwind
.fnend
.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 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
.end
# for module compiling
import os
from building import *
cwd = GetCurrentDir()
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
objs = objs + SConscript(os.path.join(cwd, 'nRF5_SDK_13.0.0_04a0bfd/components/SConscript'))
Return('objs')
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
from building import *
TARGET = 'rtthread_nrf52832.' + rtconfig.TARGET_EXT
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM == 'iar':
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = ['$LINK $SOURCES $LINKFLAGS -o $TARGET --map project.map'])
Export('RTT_ROOT')
Export('rtconfig')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# make a building
DoBuilding(TARGET, objs)
......@@ -25,13 +25,20 @@
#include <shell.h>
#endif
void rt_init_thread_entry(void* parameter)
{
}
int rt_application_init(void)
{
/* Set finsh device */
#ifdef RT_USING_FINSH
/* initialize finsh */
finsh_system_init();
#endif
rt_thread_t tid;
tid = rt_thread_create("init", rt_init_thread_entry, RT_NULL, 1024,
RT_THREAD_PRIORITY_MAX / 3, 20);
if (tid != RT_NULL)
rt_thread_startup(tid);
return 0;
}
......
此差异已折叠。
此差异已折叠。
......@@ -58,7 +58,7 @@ void rtthread_startup(void)
rt_system_timer_init();
#ifdef RT_USING_HEAP
rt_system_heap_init((void*)NRF_SRAM_BEGIN, (void*)NRF_SRAM_END);
rt_system_heap_init((void*)NRF_SRAM_BEGIN, (void*)CHIP_SRAM_END);
#endif
/* init scheduler system */
......@@ -83,7 +83,7 @@ void rtthread_startup(void)
int main(void)
{
/* disable interrupt first */
rt_hw_interrupt_disable();
// rt_hw_interrupt_disable();
/* startup RT-Thread RTOS */
rtthread_startup();
......
......@@ -2,12 +2,13 @@ Import('RTT_ROOT')
Import('rtconfig')
from building import *
# get current directory
cwd = GetCurrentDir()
cwd = GetCurrentDir()
src = Glob('*.c')
CPPPATH = [cwd]
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
#remove other no use files
#SrcRemove(src, '*.c')
group = DefineGroup('Board', src, depend = [''], CPPPATH = CPPPATH)
Return('group')
Return('group')
\ No newline at end of file
#include "board.h"
#include "uart.h"
#include "app_util_platform.h"
#include "nrf_drv_common.h"
#include "nrf_systick.h"
#include "nrf_rtc.h"
#include "nrf_drv_clock.h"
#include "softdevice_handler.h"
#include "nrf_drv_uart.h"
#include "nrf_gpio.h"
#include <rtthread.h>
static rt_bool_t osready = RT_FALSE;
#if 0
/*******************************************************************************
* Function Name : SysTick_Configuration
* Description : Configures the SysTick for OS tick.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SysTick_Configuration(void)
{
nrf_drv_common_irq_enable(SysTick_IRQn, APP_TIMER_CONFIG_IRQ_PRIORITY);
nrf_systick_load_set(SystemCoreClock / RT_TICK_PER_SECOND);
nrf_systick_val_clear();
nrf_systick_csr_set(NRF_SYSTICK_CSR_CLKSOURCE_CPU | NRF_SYSTICK_CSR_TICKINT_ENABLE
| NRF_SYSTICK_CSR_ENABLE);
}
/**
* This is the timer interrupt service routine.
*
*/
void SysTick_Handler(void)
{
if (osready)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
}
#else
#define TICK_RATE_HZ RT_TICK_PER_SECOND
#define SYSTICK_CLOCK_HZ ( 32768UL )
#define NRF_RTC_REG NRF_RTC1
/* IRQn used by the selected RTC */
#define NRF_RTC_IRQn RTC1_IRQn
/* Constants required to manipulate the NVIC. */
#define NRF_RTC_PRESCALER ( (uint32_t) (ROUNDED_DIV(SYSTICK_CLOCK_HZ, TICK_RATE_HZ) - 1) )
/* Maximum RTC ticks */
#define NRF_RTC_MAXTICKS ((1U<<24)-1U)
static volatile uint32_t m_tick_overflow_count = 0;
#define NRF_RTC_BITWIDTH 24
#define OSTick_Handler RTC1_IRQHandler
#define EXPECTED_IDLE_TIME_BEFORE_SLEEP 2
void SysTick_Configuration(void)
{
nrf_drv_clock_lfclk_request(NULL);
/* Configure SysTick to interrupt at the requested rate. */
nrf_rtc_prescaler_set(NRF_RTC_REG, NRF_RTC_PRESCALER);
nrf_rtc_int_enable (NRF_RTC_REG, RTC_INTENSET_TICK_Msk);
nrf_rtc_task_trigger (NRF_RTC_REG, NRF_RTC_TASK_CLEAR);
nrf_rtc_task_trigger (NRF_RTC_REG, NRF_RTC_TASK_START);
nrf_rtc_event_enable(NRF_RTC_REG, RTC_EVTEN_OVRFLW_Msk);
NVIC_SetPriority(NRF_RTC_IRQn, 0xF);
NVIC_EnableIRQ(NRF_RTC_IRQn);
}
void OSTick_Handler( void )
{
nrf_rtc_event_clear(NRF_RTC_REG, NRF_RTC_EVENT_COMPARE_0);
uint32_t systick_counter = nrf_rtc_counter_get(NRF_RTC_REG);
nrf_rtc_event_clear(NRF_RTC_REG, NRF_RTC_EVENT_TICK);
/* check for overflow in TICK counter */
if(nrf_rtc_event_pending(NRF_RTC_REG, NRF_RTC_EVENT_OVERFLOW))
{
nrf_rtc_event_clear(NRF_RTC_REG, NRF_RTC_EVENT_OVERFLOW);
m_tick_overflow_count++;
}
{
uint32_t diff;
diff = ((m_tick_overflow_count << NRF_RTC_BITWIDTH) + systick_counter) - rt_tick_get();
while((diff--) > 0)
{
if (osready)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
}
}
}
static void _sleep_ongo( uint32_t sleep_tick )
{
/*
* Implementation note:
*
* To help debugging the option configUSE_TICKLESS_IDLE_SIMPLE_DEBUG was presented.
* This option would make sure that even if program execution was stopped inside
* this function no more than expected number of ticks would be skipped.
*
* Normally RTC works all the time even if firmware execution was stopped
* and that may lead to skipping too much of ticks.
*/
uint32_t enterTime;
uint32_t entry_tick;
/* Make sure the SysTick reload value does not overflow the counter. */
if ( sleep_tick > NRF_RTC_MAXTICKS - EXPECTED_IDLE_TIME_BEFORE_SLEEP )
{
sleep_tick = NRF_RTC_MAXTICKS - EXPECTED_IDLE_TIME_BEFORE_SLEEP;
}
rt_enter_critical();
enterTime = nrf_rtc_counter_get(NRF_RTC_REG);
// if ( eTaskConfirmSleepModeStatus() != eAbortSleep )
{
uint32_t wakeupTime = (enterTime + sleep_tick) & NRF_RTC_MAXTICKS;
/* Stop tick events */
nrf_rtc_int_disable(NRF_RTC_REG, NRF_RTC_INT_TICK_MASK);
/* Configure CTC interrupt */
nrf_rtc_cc_set(NRF_RTC_REG, 0, wakeupTime);
nrf_rtc_event_clear(NRF_RTC_REG, NRF_RTC_EVENT_COMPARE_0);
nrf_rtc_int_enable(NRF_RTC_REG, NRF_RTC_INT_COMPARE0_MASK);
entry_tick = rt_tick_get();
__DSB();
if ( sleep_tick > 0 )
{
#ifdef SOFTDEVICE_PRESENT
if (softdevice_handler_is_enabled())
{
uint32_t err_code = sd_app_evt_wait();
APP_ERROR_CHECK(err_code);
}
else
#endif
{
/* No SD - we would just block interrupts globally.
* BASEPRI cannot be used for that because it would prevent WFE from wake up.
*/
do{
__WFE();
} while (0 == (NVIC->ISPR[0] | NVIC->ISPR[1]));
}
}
nrf_rtc_int_disable(NRF_RTC_REG, NRF_RTC_INT_COMPARE0_MASK);
nrf_rtc_event_clear(NRF_RTC_REG, NRF_RTC_EVENT_COMPARE_0);
/* Correct the system ticks */
{
nrf_rtc_event_clear(NRF_RTC_REG, NRF_RTC_EVENT_TICK);
nrf_rtc_int_enable (NRF_RTC_REG, NRF_RTC_INT_TICK_MASK);
/* It is important that we clear pending here so that our corrections are latest and in sync with tick_interrupt handler */
NVIC_ClearPendingIRQ(NRF_RTC_IRQn);
}
rt_kprintf("entry tick:%u, expected:%u, current tick:%u\n", entry_tick, sleep_tick, rt_tick_get());
}
rt_exit_critical();
}
#endif
void rt_os_ready(void)
{
osready = 1;
}
void rt_hw_system_powersave(void)
{
uint32_t sleep_tick;
sleep_tick = rt_timer_next_timeout_tick() - rt_tick_get();
if ( sleep_tick >= EXPECTED_IDLE_TIME_BEFORE_SLEEP)
{
// rt_kprintf("sleep entry:%u\n", rt_tick_get());
_sleep_ongo( sleep_tick );
}
}
void rt_hw_board_init(void)
{
// sd_power_dcdc_mode_set(NRF_POWER_DCDC_ENABLE);
/* Activate deep sleep mode */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
nrf_drv_clock_init();
// nrf_drv_clock_hfclk_request(0);
SysTick_Configuration();
rt_thread_idle_sethook(rt_hw_system_powersave);
rt_hw_uart_init();
#ifdef RT_USING_CONSOLE
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
}
#ifndef _BOARD_H_
#define _BOARD_H_
#include <rtthread.h>
#include "nrf.h"
#define CHIP_SRAM_END (0x20000000 + 64*1024)
void rt_hw_board_init(void);
void rt_os_ready(void);
#endif
#include "board.h"
#include "uart.h"
#include "nrf_drv_common.h"
#include "nrf_drv_uart.h"
#include "app_util_platform.h"
#include "nrf_gpio.h"
#include <rtdevice.h>
static struct rt_serial_device _serial0_0;
#if USE_UART0_1
static struct rt_serial_device _serial0_1;
#endif
typedef struct
{
struct rt_serial_device *serial;
nrf_drv_uart_t uart;
uint32_t rx_pin;
uint32_t tx_pin;
} UART_CFG_T;
UART_CFG_T uart0 = {
.uart = NRF_DRV_UART_INSTANCE(0),
#ifdef RT_USING_CONSOLE
.rx_pin = 3,
.tx_pin = 4
#else
.rx_pin = 19,
.tx_pin = 20
#endif
};
#if USE_UART0_1
UART_CFG_T uart1 = {
.uart = NRF_DRV_UART_INSTANCE(0),
.rx_pin = 3,
.tx_pin = 4
};
#endif
UART_CFG_T *working_cfg = RT_NULL;
void UART0_IRQHandler(void)
{
if (nrf_uart_int_enable_check(NRF_UART0, NRF_UART_INT_MASK_ERROR)
&& nrf_uart_event_check(NRF_UART0, NRF_UART_EVENT_ERROR))
{
nrf_uart_event_clear(NRF_UART0, NRF_UART_EVENT_ERROR);
}
if (nrf_uart_int_enable_check(NRF_UART0, NRF_UART_INT_MASK_RXDRDY)
&& nrf_uart_event_check(NRF_UART0, NRF_UART_EVENT_RXDRDY))
{
rt_hw_serial_isr(working_cfg->serial, RT_SERIAL_EVENT_RX_IND);
}
if (nrf_uart_int_enable_check(NRF_UART0, NRF_UART_INT_MASK_TXDRDY)
&& nrf_uart_event_check(NRF_UART0, NRF_UART_EVENT_TXDRDY))
{
rt_hw_serial_isr(working_cfg->serial, RT_SERIAL_EVENT_TX_DONE);
}
if (nrf_uart_event_check(NRF_UART0, NRF_UART_EVENT_RXTO))
{
rt_hw_serial_isr(working_cfg->serial, RT_SERIAL_EVENT_RX_TIMEOUT);
}
}
static rt_err_t _uart_cfg(struct rt_serial_device *serial, struct serial_configure *cfg)
{
nrf_drv_uart_config_t config = NRF_DRV_UART_DEFAULT_CONFIG;
UART_CFG_T *instance = &uart0;
RT_ASSERT(serial != RT_NULL);
RT_ASSERT(cfg != RT_NULL);
if (serial->parent.user_data != RT_NULL)
{
instance = (UART_CFG_T*)serial->parent.user_data;
}
nrf_uart_disable(instance->uart.reg.p_uart);
switch (cfg->baud_rate)
{
case 115200:
config.baudrate = NRF_UART_BAUDRATE_115200;
break;
case 9600:
config.baudrate = NRF_UART_BAUDRATE_9600;
break;
default:
config.baudrate = NRF_UART_BAUDRATE_115200;
break;
}
if (cfg->parity == PARITY_NONE)
{
config.parity = NRF_UART_PARITY_EXCLUDED;
}
else
{
config.parity = NRF_UART_PARITY_INCLUDED;
}
config.hwfc = NRF_UART_HWFC_DISABLED;
config.interrupt_priority = APP_IRQ_PRIORITY_LOWEST;
config.pselcts = 0;
config.pselrts = 0;
config.pselrxd = instance->rx_pin;
config.pseltxd = instance->tx_pin;
nrf_gpio_pin_set(config.pseltxd);
nrf_gpio_cfg_output(config.pseltxd);
nrf_gpio_pin_clear(config.pseltxd);
nrf_gpio_cfg_input(config.pselrxd, NRF_GPIO_PIN_NOPULL);
nrf_uart_baudrate_set(instance->uart.reg.p_uart, config.baudrate);
nrf_uart_configure(instance->uart.reg.p_uart, config.parity, config.hwfc);
nrf_uart_txrx_pins_set(instance->uart.reg.p_uart, config.pseltxd, config.pselrxd);
if (config.hwfc == NRF_UART_HWFC_ENABLED)
{
nrf_uart_hwfc_pins_set(instance->uart.reg.p_uart, config.pselrts, config.pselcts);
}
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_TXDRDY);
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_RXDRDY);
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_RXTO);
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_ERROR);
nrf_uart_int_enable(instance->uart.reg.p_uart, NRF_UART_INT_MASK_RXDRDY | NRF_UART_INT_MASK_RXTO | NRF_UART_INT_MASK_ERROR);
nrf_drv_common_irq_enable(nrf_drv_get_IRQn((void *)instance->uart.reg.p_uart), config.interrupt_priority);
nrf_uart_enable(instance->uart.reg.p_uart);
// nrf_uart_task_trigger(instance->uart.reg.p_uart, NRF_UART_TASK_STARTRX);
working_cfg = instance;
return RT_EOK;
}
static rt_err_t _uart_ctrl(struct rt_serial_device *serial, int cmd, void *arg)
{
UART_CFG_T *instance = working_cfg;
RT_ASSERT(serial != RT_NULL);
if (serial->parent.user_data != RT_NULL)
{
instance = (UART_CFG_T*)serial->parent.user_data;
}
switch (cmd)
{
/* disable interrupt */
case RT_DEVICE_CTRL_CLR_INT:
nrf_uart_task_trigger(instance->uart.reg.p_uart, NRF_UART_TASK_STOPRX);
nrf_uart_int_disable(instance->uart.reg.p_uart, NRF_UART_INT_MASK_RXDRDY
| NRF_UART_INT_MASK_RXTO
| NRF_UART_INT_MASK_ERROR);
nrf_drv_common_irq_disable(nrf_drv_get_IRQn((void *)instance->uart.reg.p_uart));
break;
/* enable interrupt */
case RT_DEVICE_CTRL_SET_INT:
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_RXDRDY);
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_RXTO);
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_ERROR);
/* Enable RX interrupt. */
nrf_uart_int_enable(instance->uart.reg.p_uart, NRF_UART_INT_MASK_RXDRDY
| NRF_UART_INT_MASK_RXTO
| NRF_UART_INT_MASK_ERROR);
nrf_drv_common_irq_enable(nrf_drv_get_IRQn((void *)instance->uart.reg.p_uart), APP_IRQ_PRIORITY_LOWEST);
nrf_uart_task_trigger(instance->uart.reg.p_uart, NRF_UART_TASK_STARTRX);
break;
case RT_DEVICE_CTRL_CUSTOM:
if ((rt_uint32_t)(arg) == UART_CONFIG_BAUD_RATE_9600)
{
instance->serial->config.baud_rate = 9600;
nrf_uart_baudrate_set(instance->uart.reg.p_uart, NRF_UART_BAUDRATE_9600);
}
else if ((rt_uint32_t)(arg) == UART_CONFIG_BAUD_RATE_115200)
{
instance->serial->config.baud_rate = 115200;
nrf_uart_baudrate_set(instance->uart.reg.p_uart, NRF_UART_BAUDRATE_115200);
}
// _uart_cfg(instance->serial, &(instance->serial->config));
// nrf_uart_task_trigger(instance->uart.reg.p_uart, NRF_UART_TASK_STARTRX);
break;
case RT_DEVICE_CTRL_PIN:
if (working_cfg != instance)
{
_uart_cfg(instance->serial, &(instance->serial->config));
}
break;
case RT_DEVICE_POWERSAVE:
nrf_uart_disable(instance->uart.reg.p_uart);
nrf_uart_txrx_pins_disconnect(instance->uart.reg.p_uart);
nrf_gpio_pin_clear(instance->rx_pin);
nrf_gpio_cfg_output(instance->rx_pin);
nrf_gpio_pin_clear(instance->tx_pin);
nrf_gpio_cfg_output(instance->tx_pin);
break;
case RT_DEVICE_WAKEUP:
_uart_cfg(instance->serial, &(instance->serial->config));
break;
default:
return RT_ERROR;
}
return RT_EOK;
}
static int _uart_putc(struct rt_serial_device *serial, char c)
{
UART_CFG_T *instance = working_cfg;
RT_ASSERT(serial != RT_NULL);
if (serial->parent.user_data != RT_NULL)
{
instance = (UART_CFG_T*)serial->parent.user_data;
}
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_TXDRDY);
nrf_uart_task_trigger(instance->uart.reg.p_uart, NRF_UART_TASK_STARTTX);
nrf_uart_txd_set(instance->uart.reg.p_uart, (uint8_t)c);
while (!nrf_uart_event_check(instance->uart.reg.p_uart, NRF_UART_EVENT_TXDRDY))
{
}
return 1;
}
static int _uart_getc(struct rt_serial_device *serial)
{
int ch = -1;
UART_CFG_T *instance = working_cfg;
RT_ASSERT(serial != RT_NULL);
if (serial->parent.user_data != RT_NULL)
{
instance = (UART_CFG_T*)serial->parent.user_data;
}
if (nrf_uart_event_check(instance->uart.reg.p_uart, NRF_UART_EVENT_RXDRDY))
{
nrf_uart_event_clear(instance->uart.reg.p_uart, NRF_UART_EVENT_RXDRDY);
ch = (int)(nrf_uart_rxd_get(instance->uart.reg.p_uart));
}
return ch;
}
static struct rt_uart_ops _uart_ops = {
_uart_cfg,
_uart_ctrl,
_uart_putc,
_uart_getc
};
void rt_hw_uart_init(void)
{
struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
config.bufsz = RT_SERIAL_RB_BUFSZ;
_serial0_0.config = config;
_serial0_0.ops = &_uart_ops;
uart0.serial = &_serial0_0;
rt_hw_serial_register(&_serial0_0, "uart0", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, &uart0);
#if USE_UART0_1
config.bufsz = UART0_RB_SIZE;
_serial0_1.config = config;
_serial0_1.ops = &_uart_ops;
uart1.serial = &_serial0_1;
rt_hw_serial_register(&_serial0_1, "uart1", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, &uart1);
#endif
}
#ifndef _UART_H_
#define _UART_H_
#define RT_DEVICE_CTRL_CUSTOM 0x20
#define RT_DEVICE_CTRL_PIN 0x21
#define RT_DEVICE_POWERSAVE 0x22
#define RT_DEVICE_WAKEUP 0x23
#define UART_CONFIG_BAUD_RATE_9600 1
#define UART_CONFIG_BAUD_RATE_115200 2
#define UART0_RB_SIZE 1024
// #define USE_UART0_1 0
void rt_hw_uart_init(void);
#endif
/*
* File : board.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2015 RT-Thread Develop Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2015-11-11 Xue Liu Initial for nRF52
*/
#include <rthw.h>
#include <rtthread.h>
#include <nrf52.h>
#include <nrf52_bitfields.h>
#include "board.h"
#include "uart.h"
/**
* @addtogroup NRF52832
*/
/** @brief: Function for handling the Systick interrupts.
*/
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase(); //This function will notify kernel there is one tick passed
/* leave interrupt */
rt_interrupt_leave();
}
/**
* This function will initial NRF52832 board.
*/
void rt_hw_board_init()
{
/* Configure the SysTick */
SysTick_Config(SystemCoreClock / RT_TICK_PER_SECOND);
/* Initial usart deriver, and set console device */
rt_hw_uart_init();
#ifdef RT_USING_CONSOLE
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
}
/*@}*/
/*
* File : board.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
*/
#ifndef __BOARD_H__
#define __BOARD_H__
void rt_hw_board_init(void);
#endif
/*
* File : uart.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2015 RT-Thread Develop Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdio.h>
#include <rthw.h>
#include <rtdevice.h>
#include "board.h"
#include "uart.h"
#include <nrf_gpio.h>
#define UART_RX_BUFSZ 512
rt_uint8_t rx_buffer[UART_RX_BUFSZ];
struct nrf52832_uart
{
struct rt_device parent;
struct rt_ringbuffer rx_rb;
} uart_device;
void UART0_IRQHandler(void)
{
rt_ubase_t level;
struct nrf52832_uart* uart = &uart_device;
level = rt_hw_interrupt_disable();
// Wait for RXD data to be received
while (NRF_UART0->EVENTS_RXDRDY != 1) ;
NRF_UART0->EVENTS_RXDRDY = 0;
rt_hw_interrupt_enable(level);
/* [Handling the data received over UART] */
rt_ringbuffer_putchar_force(&(uart->rx_rb), (rt_uint8_t)NRF_UART0->RXD);
/* invoke callback */
if(uart->parent.rx_indicate != RT_NULL)
{
uart->parent.rx_indicate(&uart->parent, rt_ringbuffer_data_len(&uart->rx_rb));
}
}
static rt_err_t rt_uart_init (rt_device_t dev)
{
/* UART Initialization and Enable */
/** @snippet [Configure UART RX and TX pin] */
nrf_gpio_cfg_output(TX_PIN_NUMBER);
nrf_gpio_cfg_input(RX_PIN_NUMBER, NRF_GPIO_PIN_NOPULL);
NRF_UART0->PSELTXD = TX_PIN_NUMBER;
NRF_UART0->PSELRXD = RX_PIN_NUMBER;
/** @snippet [Configure UART RX and TX pin] */
if (HWFC)
{
nrf_gpio_cfg_output(RTS_PIN_NUMBER);
nrf_gpio_cfg_input(CTS_PIN_NUMBER, NRF_GPIO_PIN_NOPULL);
NRF_UART0->PSELCTS = CTS_PIN_NUMBER;
NRF_UART0->PSELRTS = RTS_PIN_NUMBER;
NRF_UART0->CONFIG = (UART_CONFIG_HWFC_Enabled << UART_CONFIG_HWFC_Pos);
}
NRF_UART0->BAUDRATE = (UART_BAUDRATE_BAUDRATE_Baud38400 << UART_BAUDRATE_BAUDRATE_Pos);
NRF_UART0->ENABLE = (UART_ENABLE_ENABLE_Enabled << UART_ENABLE_ENABLE_Pos);
NRF_UART0->TASKS_STARTTX = 1;
NRF_UART0->TASKS_STARTRX = 1;
NRF_UART0->EVENTS_RXDRDY = 0;
NRF_UART0->INTENSET = (UART_INTENSET_RXDRDY_Enabled << UART_INTENSET_RXDRDY_Pos);
NVIC_EnableIRQ(UART0_IRQn);
return RT_EOK;
}
static rt_err_t rt_uart_open(rt_device_t dev, rt_uint16_t oflag)
{
RT_ASSERT(dev != RT_NULL);
if (dev->flag & RT_DEVICE_FLAG_INT_RX)
{
/* Enable the UART Interrupt */
NVIC_EnableIRQ(UART0_IRQn);
}
return RT_EOK;
}
static rt_err_t rt_uart_close(rt_device_t dev)
{
RT_ASSERT(dev != RT_NULL);
if (dev->flag & RT_DEVICE_FLAG_INT_RX)
{
/* Disable the UART Interrupt */
NVIC_DisableIRQ(UART0_IRQn);
}
return RT_EOK;
}
static rt_size_t rt_uart_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_size_t size)
{
rt_size_t length;
struct nrf52832_uart *uart = (struct nrf52832_uart*)dev;
/* interrupt receive */
rt_base_t level;
RT_ASSERT(uart != RT_NULL);
/* disable interrupt */
level = rt_hw_interrupt_disable();
length = rt_ringbuffer_get(&(uart->rx_rb), buffer, size);
/* enable interrupt */
rt_hw_interrupt_enable(level);
return length;
}
static rt_size_t rt_uart_write(rt_device_t dev, rt_off_t pos, const void* buffer, rt_size_t size)
{
char *ptr;
ptr = (char*) buffer;
if (dev->open_flag & RT_DEVICE_FLAG_STREAM)
{
/* stream mode */
while (size)
{
if (*ptr == '\n')
{
NRF_UART0->TXD = (uint8_t)'\r';
// Wait for TXD data to be sent.
while (NRF_UART0->EVENTS_TXDRDY != 1) ;
NRF_UART0->EVENTS_TXDRDY = 0;
}
NRF_UART0->TXD = (uint8_t)(*ptr);
// Wait for TXD data to be sent.
while (NRF_UART0->EVENTS_TXDRDY != 1) ;
NRF_UART0->EVENTS_TXDRDY = 0;
ptr ++;
size --;
}
}
else
{
while ( size != 0 )
{
NRF_UART0->TXD = (uint8_t)(*ptr);
// Wait for TXD data to be sent.
while (NRF_UART0->EVENTS_TXDRDY != 1) ;
NRF_UART0->EVENTS_TXDRDY = 0;
ptr++;
size--;
}
}
return (rt_size_t) ptr - (rt_size_t) buffer;
}
void rt_hw_uart_init(void)
{
struct nrf52832_uart* uart;
/* get uart device */
uart = &uart_device;
/* device initialization */
uart->parent.type = RT_Device_Class_Char;
rt_ringbuffer_init(&(uart->rx_rb), rx_buffer, sizeof(rx_buffer));
/* device interface */
uart->parent.init = rt_uart_init;
uart->parent.open = rt_uart_open;
uart->parent.close = rt_uart_close;
uart->parent.read = rt_uart_read;
uart->parent.write = rt_uart_write;
uart->parent.control = RT_NULL;
uart->parent.user_data = RT_NULL;
rt_device_register(&uart->parent, "uart0", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX);
}
/*
* File : uart.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2015, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
*/
#ifndef __UART_H__
#define __UART_H__
#define RX_PIN_NUMBER 8
#define TX_PIN_NUMBER 6
#define CTS_PIN_NUMBER 7
#define RTS_PIN_NUMBER 5
#define HWFC false
void rt_hw_uart_init(void);
#endif
Import('RTT_ROOT')
Import('rtconfig')
from building import *
# get current directory
cwd = GetCurrentDir()
BLE_COMMON = Glob('./components/ble/common/*.c')
SrcRemove(BLE_COMMON, 'ble_conn_state.c')
BLE_GATT = Glob('./components/ble/nrf_ble_gatt/*.c')
BLE_ADVERTISING = Glob('./components/ble/ble_advertising/*.c')
BLE_SERVICE = Glob('./components/ble/ble_services/ble_nus/*.c')
BLE_SRC = BLE_COMMON + BLE_GATT + BLE_SERVICE + BLE_ADVERTISING
SOFTDEVICE = Glob('./components/softdevice/common/softdevice_handler/*.c')
SrcRemove(SOFTDEVICE, 'softdevice_handler_appsh.c')
BLE_STACK_SRC = BLE_SRC + SOFTDEVICE
path = [cwd + '/components']
path += [cwd + '/components/softdevice/common/softdevice_handler']
path += [cwd + '/components/softdevice/s132/headers']
path += [cwd + '/components/softdevice/s132/headers/nrf52']
path += [cwd + '/components/ble/common']
path += [cwd + '/components/ble/nrf_ble_gatt']
path += [cwd + '/components/ble/ble_advertising']
path += [cwd + '/components/ble/ble_services/ble_nus']
CPPDEFINES = ['BLE_STACK_SUPPORT_REQD', 'NRF_SD_BLE_API_VERSION=4', 'S132', 'SOFTDEVICE_PRESENT']
group = DefineGroup('BLE_STACK', BLE_STACK_SRC, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
Return('group')
Import('RTT_ROOT')
Import('rtconfig')
from building import *
# get current directory
cwd = GetCurrentDir()
DriversDir = cwd + '/drivers_nrf/'
DeviceDrivers = [DriversDir + 'hal/nrf_saadc.c']
DeviceDrivers += [DriversDir + 'common/nrf_drv_common.c']
#DeviceDrivers += [DriversDir + 'uart/nrf_drv_uart.c']
DeviceDrivers += [DriversDir + 'clock/nrf_drv_clock.c']
DeviceDrivers += [DriversDir + 'gpiote/nrf_drv_gpiote.c']
DeviceDrivers += [DriversDir + 'pwm/nrf_drv_pwm.c']
DeviceDrivers += [DriversDir + 'saadc/nrf_drv_saadc.c']
Libraries_dir = cwd + '/libraries/'
Libraries_src = Glob(Libraries_dir + 'log/src/*.c')
Libraries_src += Glob(Libraries_dir + 'timer/app_timer_rtthread.c')
Libraries_src += Glob(Libraries_dir + 'util/*.c')
Libraries_src += Glob(Libraries_dir + 'fstorage/fstorage.c')
Libraries_src += Glob(Libraries_dir + 'strerror/nrf_strerror.c')
src = DeviceDrivers + Libraries_src
path = [cwd]
path += [cwd + '/device']
path += [cwd + '/drivers_nrf/delay']
path += [cwd + '/drivers_nrf/uart']
path += [cwd + '/drivers_nrf/clock']
path += [cwd + '/drivers_nrf/gpiote']
path += [cwd + '/drivers_nrf/common']
path += [cwd + '/drivers_nrf/hal']
path += [cwd + '/drivers_nrf/pwm']
path += [DriversDir + 'saadc']
path += [Libraries_dir + 'util']
path += [Libraries_dir + 'timer']
path += [Libraries_dir + 'fstorage']
path += [Libraries_dir + 'experimental_section_vars']
path += [Libraries_dir + 'log']
path += [Libraries_dir + 'log/src']
path += [Libraries_dir + 'strerror']
path += [cwd + '/toolchain/cmsis/include']
CPPDEFINES = ['RTTHREAD', 'SWI_DISABLE0', 'CONFIG_GPIO_AS_PINRESET', 'NRF52', 'NRF52832_XXAA']
CPPDEFINES += ['NRF52_PAN_12', 'NRF52_PAN_15', 'NRF52_PAN_20', 'NRF52_PAN_31', 'NRF52_PAN_36']
CPPDEFINES += ['NRF52_PAN_51', 'NRF52_PAN_54', 'NRF52_PAN_55', 'NRF52_PAN_58', 'NRF52_PAN_64', 'NRF52_PAN_74']
group = DefineGroup('NRF_DRIVERS', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
Return('group')
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#include "sdk_common.h"
#if NRF_MODULE_ENABLED(ANT_CHANNEL_CONFIG)
#include "nrf_error.h"
#include "ant_channel_config.h"
#include "ant_interface.h"
#include "ant_parameters.h"
uint32_t ant_channel_init(ant_channel_config_t const * p_config)
{
uint32_t err_code;
// Set Channel Number.
err_code = sd_ant_channel_assign(p_config->channel_number,
p_config->channel_type,
p_config->network_number,
p_config->ext_assign);
VERIFY_SUCCESS(err_code);
// Set Channel ID.
err_code = sd_ant_channel_id_set(p_config->channel_number,
p_config->device_number,
p_config->device_type,
p_config->transmission_type);
VERIFY_SUCCESS(err_code);
// Set Channel RF frequency.
err_code = sd_ant_channel_radio_freq_set(p_config->channel_number, p_config->rf_freq);
VERIFY_SUCCESS(err_code);
// Set Channel period.
if (!(p_config->ext_assign & EXT_PARAM_ALWAYS_SEARCH) && (p_config->channel_period != 0))
{
err_code = sd_ant_channel_period_set(p_config->channel_number, p_config->channel_period);
}
#if ANT_CONFIG_ENCRYPTED_CHANNELS > 0
VERIFY_SUCCESS(err_code);
err_code = ant_channel_encrypt_config(p_config->channel_type , p_config->channel_number, p_config->p_crypto_settings);
#endif
return err_code;
}
#endif // NRF_MODULE_ENABLED(ANT_CHANNEL_CONFIG)
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#ifndef ANT_CHANNEL_CONFIG_H__
#define ANT_CHANNEL_CONFIG_H__
/** @file
*
* @defgroup ant_channel_config ANT channel configuration
* @{
* @ingroup ant_sdk_utils
* @brief ANT channel configuration module.
*/
#include <stdint.h>
#include "sdk_config.h"
#ifndef ANT_CONFIG_ENCRYPTED_CHANNELS
#error Undefined ANT_CONFIG_ENCRYPTED_CHANNELS. It should be defined in sdk_config.h file.
#elif ANT_CONFIG_ENCRYPTED_CHANNELS > 0
#include "ant_encrypt_config.h"
#endif
#ifdef __cplusplus
extern "C" {
#endif
/**@brief ANT channel configuration structure. */
typedef struct
{
uint8_t channel_number; ///< Assigned channel number.
uint8_t channel_type; ///< Channel type (see Assign Channel Parameters in ant_parameters.h: @ref ant_parameters).
uint8_t ext_assign; ///< Extended assign (see Ext. Assign Channel Parameters in ant_parameters.h: @ref ant_parameters).
uint8_t rf_freq; ///< Radio frequency offset from 2400 MHz (for example, 2466 MHz, rf_freq = 66).
uint8_t transmission_type; ///< Transmission type.
uint8_t device_type; ///< Device type.
uint16_t device_number; ///< Device number.
uint16_t channel_period; ///< The period in 32 kHz counts.
uint8_t network_number; ///< Network number denoting the network key.
#if ANT_CONFIG_ENCRYPTED_CHANNELS > 0
ant_encrypt_channel_settings_t * p_crypto_settings; ///< Pointer to cryptographic settings, NULL if this configuration have to be omitted.
#endif
} ant_channel_config_t;
/**@brief Function for configuring the ANT channel.
*
* @param[in] p_config Pointer to the channel configuration structure.
*
* @retval NRF_SUCCESS If the channel was successfully configured. Otherwise, an error code is returned.
*/
uint32_t ant_channel_init(ant_channel_config_t const * p_config);
#ifdef __cplusplus
}
#endif
#endif // ANT_CHANNEL_CONFIG_H__
/** @} */
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#include "sdk_common.h"
#if NRF_MODULE_ENABLED(ANT_ENCRYPT_CONFIG)
#include <stdlib.h>
#include "ant_encrypt_config.h"
#include "ant_interface.h"
#include "ant_parameters.h"
#ifdef ANT_ENCRYPT_NEGOTIATION_SLAVE_ENABLED
#include "ant_encrypt_negotiation_slave.h"
#endif
/*lint -e551 -save*/
/** Flag for checking if stack was configured for encryption. */
static bool m_stack_encryption_configured = false;
/*lint -restore */
/** Pointer to handler of module's events. */
static ant_encryp_user_handler_t m_ant_enc_evt_handler = NULL;
static ret_code_t ant_enc_advance_burs_config_apply(
ant_encrypt_adv_burst_settings_t const * const p_adv_burst_set);
ret_code_t ant_stack_encryption_config(ant_encrypt_stack_settings_t const * const p_crypto_set)
{
ret_code_t err_code;
for ( uint32_t i = 0; i < p_crypto_set->key_number; i++)
{
err_code = sd_ant_crypto_key_set(i, p_crypto_set->pp_key[i]);
VERIFY_SUCCESS(err_code);
}
if (p_crypto_set->p_adv_burst_config != NULL)
{
err_code = ant_enc_advance_burs_config_apply(p_crypto_set->p_adv_burst_config);
VERIFY_SUCCESS(err_code);
}
// subcomands LUT for @ref sd_ant_crypto_info_set calls
const uint8_t set_enc_info_param_lut[] =
{
ENCRYPTION_INFO_SET_CRYPTO_ID,
ENCRYPTION_INFO_SET_CUSTOM_USER_DATA,
ENCRYPTION_INFO_SET_RNG_SEED
};
for ( uint32_t i = 0; i < sizeof(set_enc_info_param_lut); i++)
{
if ( p_crypto_set->info.pp_array[i] != NULL)
{
err_code = sd_ant_crypto_info_set(set_enc_info_param_lut[i],
p_crypto_set->info.pp_array[i]);
VERIFY_SUCCESS(err_code);
}
}
#ifdef ANT_ENCRYPT_NEGOTIATION_SLAVE_ENABLED
// all ANT channels have unsupported slave encryption tracking (even master's channel)
ant_channel_encryp_negotiation_slave_init();
#endif
m_ant_enc_evt_handler = NULL;
m_stack_encryption_configured = true;
return NRF_SUCCESS;
}
/**
* @brief Function for configuring advanced burst settings according to encryption requirements.
*
* @param p_adv_burst_set Pointer to ANT advanced burst settings.
*
* @retval Value returned by @ref sd_ant_adv_burst_config_set.
*/
static ret_code_t ant_enc_advance_burs_config_apply(
ant_encrypt_adv_burst_settings_t const * const p_adv_burst_set)
{
uint8_t adv_burst_conf_str[ADV_BURST_CFG_MIN_SIZE] =
{ ADV_BURST_MODE_ENABLE, 0, 0, 0, 0, 0, 0, 0 };
adv_burst_conf_str[ADV_BURST_CFG_PACKET_SIZE_INDEX] = p_adv_burst_set->packet_length;
adv_burst_conf_str[ADV_BURST_CFG_REQUIRED_FEATURES] = p_adv_burst_set->required_feature;
adv_burst_conf_str[ADV_BURST_CFG_OPTIONAL_FEATURES] = p_adv_burst_set->optional_feature;
return sd_ant_adv_burst_config_set(adv_burst_conf_str, sizeof(adv_burst_conf_str));
}
ret_code_t ant_channel_encrypt_config_perform(uint8_t channel_number,
ant_encrypt_channel_settings_t * p_crypto_config)
{
return sd_ant_crypto_channel_enable(channel_number,
p_crypto_config->mode,
p_crypto_config->key_index,
p_crypto_config->decimation_rate);
}
ret_code_t ant_channel_encrypt_config(uint8_t channel_type,
uint8_t channel_number,
ant_encrypt_channel_settings_t * p_crypto_config)
{
ret_code_t err_code;
if (p_crypto_config != NULL)
{
// encryption of the stack should be initialized previously
if (m_stack_encryption_configured == false)
{
return NRF_ERROR_MODULE_NOT_INITIALZED;
}
switch (channel_type)
{
case CHANNEL_TYPE_MASTER:
err_code = ant_channel_encrypt_config_perform(channel_number, p_crypto_config);
#ifdef ANT_ENCRYPT_NEGOTIATION_SLAVE_ENABLED
ant_channel_encryp_tracking_state_set(channel_number,
ANT_ENC_CHANNEL_STAT_TRACKING_UNSUPPORTED);
#endif
break;
#ifdef ANT_ENCRYPT_NEGOTIATION_SLAVE_ENABLED
case CHANNEL_TYPE_SLAVE:
ant_slave_channel_encrypt_config(channel_number, p_crypto_config);
if (p_crypto_config->mode == ENCRYPTION_DISABLED_MODE)
{
err_code = ant_channel_encrypt_config_perform(channel_number, p_crypto_config);
ant_channel_encryp_tracking_state_set(channel_number,
ANT_ENC_CHANNEL_STAT_TRACKING_UNSUPPORTED);
}
else
{
ant_channel_encryp_tracking_state_set(channel_number,
ANT_ENC_CHANNEL_STAT_NOT_TRACKING);
err_code = NRF_SUCCESS;
}
break;
#endif
default:
err_code = NRF_ERROR_INVALID_PARAM;
break;
}
}
else
{
#ifdef ANT_ENCRYPT_NEGOTIATION_SLAVE_ENABLED
ant_channel_encryp_tracking_state_set(channel_number,
ANT_ENC_CHANNEL_STAT_TRACKING_UNSUPPORTED);
#endif
err_code = NRF_SUCCESS;
}
return err_code;
}
/** @brief Function for calling the handler of module events.*/
static void ant_encrypt_user_handler_try_to_run(uint8_t ant_channel, ant_encrypt_user_evt_t event)
{
if (m_ant_enc_evt_handler != NULL)
{
m_ant_enc_evt_handler(ant_channel, event);
}
}
void ant_encrypt_event_handler(ant_evt_t * p_ant_evt)
{
uint8_t const ant_channel = p_ant_evt->channel;
#ifdef ANT_ENCRYPT_NEGOTIATION_SLAVE_ENABLED
ant_slave_encrypt_negotiation(p_ant_evt);
#endif
switch (p_ant_evt->event)
{
case EVENT_RX_FAIL_GO_TO_SEARCH:
ant_encrypt_user_handler_try_to_run(ant_channel, ANT_ENC_EVT_CHANNEL_LOST);
break;
case EVENT_ENCRYPT_NEGOTIATION_SUCCESS:
ant_encrypt_user_handler_try_to_run(ant_channel, ANT_ENC_EVT_NEGOTIATION_SUCCESS);
break;
case EVENT_ENCRYPT_NEGOTIATION_FAIL:
ant_encrypt_user_handler_try_to_run(ant_channel, ANT_ENC_EVT_NEGOTIATION_FAIL);
break;
}
}
void ant_enc_event_handler_register(ant_encryp_user_handler_t user_handler_func)
{
m_ant_enc_evt_handler = user_handler_func;
}
#endif // NRF_MODULE_ENABLED(ANT_ENCRYPT_CONFIG)
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#ifndef ANT_ENCRYPT_CONFIG__
#define ANT_ENCRYPT_CONFIG__
/**@file
*
* @defgroup ant_encrypt_config ANT encryption configuration
* @{
* @ingroup ant_sdk_utils
*
* @brief Encryption configuration for the ANT stack and channels.
*
*/
#include <stdint.h>
#include "sdk_errors.h"
#include "ant_stack_handler_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/** @name Advanced burst configuration for encryption modules
* @{
*/
#define ADV_BURST_CFG_MIN_SIZE 8 ///< Minimum size of the advance burst configuration data.
#define ADV_BURST_CFG_PACKET_SIZE_INDEX 1 ///< Index of the packet size field in the configuration data.
#define ADV_BURST_CFG_REQUIRED_FEATURES 2 ///< Index of the required features field in the configuration data.
#define ADV_BURST_CFG_OPTIONAL_FEATURES 5 ///< Index of the optional features field in the configuration data.
/**@} */
/** @brief ANT channel cryptographic configuration. */
typedef struct
{
uint8_t mode; ///< Encryption mode. See the encrypted channel defines in ant_parameters.h.
uint8_t key_index; ///< Index of encryption key.
uint8_t decimation_rate; ///< Division of the master channel rate by the slave’s tracking channel rate.
} ant_encrypt_channel_settings_t;
/** @brief ANT encryption information. */
typedef union
{
uint8_t * pp_array[3]; // For array access support.
struct
{
uint8_t * p_encryption_id; ///< Pointer to the encryption ID of the device (4 bytes).
uint8_t * p_user_info; ///< Pointer to the user information string (19 bytes).
uint8_t * p_random_num_seed; ///< Pointer to the random number seed (16 bytes).
} items;
} ant_encrypt_info_settings_t;
/** @brief Advanced burst settings used by the encrypted channel. */
typedef struct
{
uint8_t packet_length; ///< RF payload size. See the advanced burst configuration defines in ant_parameters.h.
uint8_t required_feature; ///< Required advanced burst modes. See the advanced burst configuration defines in ant_parameters.h.
uint8_t optional_feature; ///< Optional advanced burst modes. See the advanced burst configuration defines in ant_parameters.h.
} ant_encrypt_adv_burst_settings_t;
/**@brief ANT stack cryptographic configuration. */
typedef struct
{
ant_encrypt_info_settings_t info; ///< Pointer to the encryption information structure.
uint8_t * * pp_key; ///< Pointer to an array for pointers to encryption keys. Each key must have a length of 16 bytes.
uint8_t key_number; ///< Number of encryption keys.
ant_encrypt_adv_burst_settings_t * p_adv_burst_config; ///< Advanced burst configuration. If NULL, the advanced burst must be configured externally.
} ant_encrypt_stack_settings_t;
/**
* @brief ANT encryption negotiation events.
*/
typedef enum
{
ANT_ENC_EVT_NEGOTIATION_SUCCESS, ///< Negotiation success.
ANT_ENC_EVT_NEGOTIATION_FAIL, ///< Negotiation failure.
ANT_ENC_EVT_CHANNEL_LOST ///< Lost a channel. It's relevant only for slave channels.
} ant_encrypt_user_evt_t;
/**
* @brief Event handler for ANT encryption user events.
*/
typedef void (* ant_encryp_user_handler_t)(uint8_t channel, ant_encrypt_user_evt_t event);
/**
* @brief Macro for initializing an ANT encryption information structure.
*
* @param[in] P_ENC_ID Pointer to the encryption ID of the device (4 bytes).
* @param[in] P_USER_INFO Pointer to the user information string (19 bytes).
* @param[in] P_RAND_NUM_SEED Pointer to the random number seed (16 bytes).
*/
#define ANT_CRYPTO_INFO_SETTINGS_INIT(P_ENC_ID, P_USER_INFO, P_RAND_NUM_SEED) \
{ \
.items = \
{ \
.p_encryption_id = P_ENC_ID, \
.p_user_info = P_USER_INFO, \
.p_random_num_seed = P_RAND_NUM_SEED \
} \
}
/**
* @brief Macro for declaring the basic cryptographic configuration for the ANT stack.
*
* This macro configures the following settings:
* - Cryptographic key
* - Encryption ID
* - Advanced burst mode with the maximum RF payload size
*
* Use @ref ANT_ENCRYPT_STACK_SETTINGS_BASE to access the created configuration instance.
*
* @param[in] NAME Name for the created data instance.
* @param[in] P_KEY Pointer to the cryptographic key (16 bytes).
* @param[in] P_ENC_ID Pointer to the encryption ID (4 bytes).
*/
#define ANT_ENCRYPT_STACK_SETTINGS_BASE_DEF(NAME, P_KEY, P_ENC_ID) \
ant_encrypt_adv_burst_settings_t NAME##_ant_enc_adv_burst_set = \
{ \
.packet_length = ADV_BURST_MODES_MAX_SIZE, \
.required_feature = 0, \
.optional_feature = 0 \
}; \
uint8_t * pp_##NAME##_key[1] = {P_KEY}; \
ant_encrypt_stack_settings_t NAME ## _ant_crypto_settings = \
{ \
.info = ANT_CRYPTO_INFO_SETTINGS_INIT(P_ENC_ID, NULL, NULL), \
.pp_key = pp_##NAME##_key, \
.key_number = 1, \
.p_adv_burst_config = &NAME##_ant_enc_adv_burst_set \
}
/** @brief Macro for accessing the configuration instance created
* by @ref ANT_ENCRYPT_STACK_SETTINGS_BASE_DEF.
*
* @param[in] NAME Name of the settings instance.
*/
#define ANT_ENCRYPT_STACK_SETTINGS_BASE(NAME) (NAME##_ant_crypto_settings)
/**
* @brief Function for applying an encryption configuration to a slave channel.
*
* This function enables encryption on a channel.
*
* This function should be used by the @ref ant_encrypt_negotiation_slave module and this module.
*
* @param[in] channel_number ANT channel number.
* @param[in] p_crypto_config Pointer to the encryption configuration.
*
* @return Value returned by @ref sd_ant_crypto_channel_enable (for example, NRF_SUCCESS if
* the configuration was successful).
*/
ret_code_t ant_channel_encrypt_config_perform(uint8_t channel_number,
ant_encrypt_channel_settings_t * p_crypto_config);
/**
* @brief Function for applying an encryption configuration to a master or slave channel.
*
* When called for a master channel, this function enables encryption
* for that channel. When called for a slave channel, it saves
* the encryption configuration for future use.
*
* This function should be used by the @ref ant_channel_config module.
*
* @param[in] channel_type ANT channel type: CHANNEL_TYPE_SLAVE or CHANNEL_TYPE_MASTER.
* @param[in] channel_num ANT channel number.
* @param[in] p_crypto_config Pointer to the encryption configuration.
*
* @retval NRF_SUCCESS If the function completed successfully.
* @retval NRF_ERROR_INVALID_PARAM If the channel type is invalid.
* @retval NRF_ERROR_MODULE_NOT_INITIALZED If the stack is not configured for encryption.
* @retval Other Otherwise, the error value returned by the @ref
* ant_channel_encrypt_config_perform function is returned.
*/
ret_code_t ant_channel_encrypt_config(uint8_t channel_type,
uint8_t channel_num,
ant_encrypt_channel_settings_t * p_crypto_config);
/**
* @brief Function for configuring the cryptographic settings of the ANT stack.
*
* @param[in] p_crypto_info_set Pointer to the settings.
*/
ret_code_t ant_stack_encryption_config(ant_encrypt_stack_settings_t const * const p_crypto_info_set);
/**
* @brief Function for handling ANT encryption events.
*
* This function should be used directly in the ANT event dispatching process.
* It serves the ANT encryption events to the registered event handler.
* If @ref ant_encrypt_negotiation_slave is used, this function is required.
*
* This function should be used by the @ref ant_encrypt_config module.
*
* @param[in] p_ant_evt Pointer to the ANT stack event message structure.
*/
void ant_encrypt_event_handler(ant_evt_t * p_ant_evt);
/**
* @brief Function for registering an event handler for ANT encryption events.
*
* The event handler should support all of the events in @ref ant_encrypt_user_evt_t.
*
* @param[in] p_handler Pointer to a handler function.
*/
void ant_enc_event_handler_register(ant_encryp_user_handler_t p_handler);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif // ANT_ENCRYPT_CONFIG__
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#include "sdk_common.h"
#if NRF_MODULE_ENABLED(ANT_ENCRYPT_NEGOTIATION_SLAVE)
#include <stdlib.h>
#include <string.h>
#include "ant_encrypt_config.h"
#include "ant_interface.h"
#include "ant_parameters.h"
#include "nrf_error.h"
#include "app_error.h"
#include "ant_encrypt_negotiation_slave.h"
/** Number of supported channels. */
#define NUMBER_OF_CHANNELS (ANT_CONFIG_TOTAL_CHANNELS_ALLOCATED)
/** Flag to block other channels from attempting to enable encryption while
* another encryption is in the process.
*/
static volatile bool m_can_enable_crypto = true;
/** Array to keep track of which channels are currently tracking. */
static ant_encrypt_tracking_state_t m_encrypt_channel_states[NUMBER_OF_CHANNELS];
/** Array for the slave channels' encryption settings. */
static ant_encrypt_channel_settings_t m_slave_channel_conf[MAX_ANT_CHANNELS];
void ant_channel_encryp_tracking_state_set(uint8_t channel_number,
ant_encrypt_tracking_state_t state)
{
m_encrypt_channel_states[channel_number] = state;
}
void ant_channel_encryp_negotiation_slave_init(void)
{
for (uint32_t channel = 0; channel < NUMBER_OF_CHANNELS; channel++)
{
ant_channel_encryp_tracking_state_set(channel, ANT_ENC_CHANNEL_STAT_TRACKING_UNSUPPORTED);
}
m_can_enable_crypto = true;
}
ant_encrypt_tracking_state_t ant_channel_encryp_tracking_state_get(uint8_t channel_number)
{
return m_encrypt_channel_states[channel_number];
}
void ant_slave_channel_encrypt_config(uint8_t channel_number,
ant_encrypt_channel_settings_t const * const p_crypto_config)
{
memcpy(&m_slave_channel_conf[channel_number], p_crypto_config,
sizeof(ant_encrypt_channel_settings_t));
}
/**@brief Function for handling ANT RX channel events.
*
* @param[in] p_event_message_buffer The ANT event message buffer.
*/
static void ant_slave_encrypt_try_enable(uint8_t ant_channel,
uint8_t ant_message_id)
{
uint32_t err_code;
ant_encrypt_tracking_state_t track_stat;
switch (ant_message_id)
{
// Broadcast data received.
case MESG_BROADCAST_DATA_ID:
track_stat = ant_channel_encryp_tracking_state_get(ant_channel);
// If the encryption has not yet been negotiated for this channel and another channel
// is not currently trying to enable encryption, enable encryption
if ((track_stat != ANT_ENC_CHANNEL_STAT_TRACKING_DECRYPTED)
&& (track_stat != ANT_ENC_CHANNEL_STAT_NEGOTIATING)
&& m_can_enable_crypto)
{
// Block other channels from trying to enable encryption until this channel
// is finished
m_can_enable_crypto = false;
ant_channel_encryp_tracking_state_set(ant_channel,
ANT_ENC_CHANNEL_STAT_NEGOTIATING);
// Enable encryption on ant_channel
err_code =
ant_channel_encrypt_config_perform(ant_channel,
&m_slave_channel_conf[ant_channel]);
APP_ERROR_CHECK(err_code);
}
break;
default:
break;
}
}
void ant_slave_encrypt_negotiation(ant_evt_t * p_ant_evt)
{
uint8_t const ant_channel = p_ant_evt->channel;
ANT_MESSAGE * p_ant_msg;
ant_encrypt_tracking_state_t track_state = ant_channel_encryp_tracking_state_get(ant_channel);
if (track_state == ANT_ENC_CHANNEL_STAT_TRACKING_UNSUPPORTED)
return;
switch (p_ant_evt->event)
{
case EVENT_RX_FAIL_GO_TO_SEARCH:
if (track_state == ANT_ENC_CHANNEL_STAT_NEGOTIATING)
{
m_can_enable_crypto = true;
}
ant_channel_encryp_tracking_state_set(ant_channel, ANT_ENC_CHANNEL_STAT_NOT_TRACKING);
break;
case EVENT_RX:
/*lint -e545 -save*/
p_ant_msg = (ANT_MESSAGE *) &(p_ant_evt->msg.evt_buffer);
/*lint -restore*/
ant_slave_encrypt_try_enable(ant_channel, p_ant_msg->ANT_MESSAGE_ucMesgID);
break;
case EVENT_ENCRYPT_NEGOTIATION_SUCCESS:
m_can_enable_crypto = true;
ant_channel_encryp_tracking_state_set(ant_channel,
ANT_ENC_CHANNEL_STAT_TRACKING_DECRYPTED);
break;
case EVENT_ENCRYPT_NEGOTIATION_FAIL:
m_can_enable_crypto = true;
ant_channel_encryp_tracking_state_set(ant_channel,
ANT_ENC_CHANNEL_STAT_TRACKING_ENCRYPTED);
break;
default:
break;
}
}
#endif // NRF_MODULE_ENABLED(ANT_ENCRYPT_NEGOTIATION_SLAVE)
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#ifndef ANT_ENCRYPT_NEGOTIATION_SLAVE_H__
#define ANT_ENCRYPT_NEGOTIATION_SLAVE_H__
/**@file
*
* @defgroup ant_encrypt_negotiation_slave ANT encryption negotiation
* @{
* @ingroup ant_sdk_utils
*
* @brief Encryption negotiation for encrypted ANT slave channels.
*
* After pairing, the slave starts negotiating the encryption with the master. After
* successful negotiation, the slave can decrypt messages from the master, and all
* future messages are sent encrypted.
*
*/
#include <stdint.h>
#include "ant_stack_handler_types.h"
#include "ant_encrypt_config.h"
#ifdef __cplusplus
extern "C" {
#endif
/** Encryption negotiation states for a slave channel. */
typedef enum
{
ANT_ENC_CHANNEL_STAT_NOT_TRACKING, ///< Not tracking the master.
ANT_ENC_CHANNEL_STAT_TRACKING_ENCRYPTED, ///< Tracking the master, but cannot decrypt messages.
ANT_ENC_CHANNEL_STAT_NEGOTIATING, ///< Encryption has been enabled and negotiation is in progress.
ANT_ENC_CHANNEL_STAT_TRACKING_DECRYPTED, ///< Tracking the master and can decrypt messages.
ANT_ENC_CHANNEL_STAT_TRACKING_UNSUPPORTED ///< Tracking unsupported on this channel.
} ant_encrypt_tracking_state_t;
/**
* @brief Function for setting the encryption negotiation state of a slave ANT channel.
*
* This function should be used by the @ref ant_encrypt_config module.
*
* @param[in] channel_number ANT channel number.
* @param[in] state State to set.
*/
void ant_channel_encryp_tracking_state_set(uint8_t channel_number,
ant_encrypt_tracking_state_t state);
/**
* @brief Function for getting the encryption negotiation state of a slave ANT channel.
*
* @param[in] channel_number ANT channel number.
*/
ant_encrypt_tracking_state_t ant_channel_encryp_tracking_state_get(uint8_t channel_number);
/**
* @brief Function for initializing the module.
*
* This function initializes internal states of the module. It should
* only be used by the @ref ant_encrypt_config module.
*
*/
void ant_channel_encryp_negotiation_slave_init(void);
/**
* @brief Function for setting the configuration for the slave channel.
*
* This function saves the channel's encryption configuration to a lookup table (LUT) for
* future usage. The configuration can then be used to enable encryption.
*
* This function is intended to be used by the @ref ant_encrypt_config module.
*
* @param[in] channel_number ANT channel number.
* @param[in] p_crypto_config Pointer to the encryption configuration.
*/
void ant_slave_channel_encrypt_config(uint8_t channel_number,
ant_encrypt_channel_settings_t const * const p_crypto_config);
/**
* @brief Function for handling ANT encryption negotiation on slave nodes.
*
* This function should be used directly in the ANT event dispatching process. It
* tries to enable slave channel encryption for all slave channels that are declared
* as encrypted channels (if appropriate master channels are found).
*
* This function should be used by the @ref ant_encrypt_config module.
*
* @param[in] p_ant_evt Pointer to the ANT stack event message structure.
*/
void ant_slave_encrypt_negotiation(ant_evt_t * p_ant_evt);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif // ANT_ENCRYPT_NEGOTIATION_SLAVE_H__
/**
* This software is subject to the ANT+ Shared Source License
* www.thisisant.com/swlicenses
* Copyright (c) Dynastream Innovations, Inc. 2012
* 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 Dynastream nor the names of its
* contributors may be used to endorse or promote products
* derived from this software without specific prior
* written permission.
*
* The following actions are prohibited:
* 1) Redistribution of source code containing the ANT+ Network
* Key. The ANT+ Network Key is available to ANT+ Adopters.
* Please refer to http://thisisant.com to become an ANT+
* Adopter and access the key.
*
* 2) Reverse engineering, decompilation, and/or disassembly of
* software provided in binary form under this license.
*
* 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 HEREBY
* 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; DAMAGE TO ANY DEVICE, 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. SOME STATES DO NOT ALLOW
* THE EXCLUSION OF INCIDENTAL OR CONSEQUENTIAL DAMAGES, SO THE
* ABOVE LIMITATIONS MAY NOT APPLY TO YOU.
*
*/
#include "crc.h"
#include "compiler_abstraction.h"
/**@brief Function for updating the current CRC-16 value for a single byte input.
*
* @param[in] current_crc The current calculated CRC-16 value.
* @param[in] byte The input data byte for the computation.
*
* @return The updated CRC-16 value, based on the input supplied.
*/
static __INLINE uint16_t crc16_get(uint16_t current_crc, uint8_t byte)
{
static const uint16_t crc16_table[16] =
{
0x0000, 0xCC01, 0xD801, 0x1400, 0xF001, 0x3C00, 0x2800, 0xE401,
0xA001, 0x6C00, 0x7800, 0xB401, 0x5000, 0x9C01, 0x8801, 0x4400
};
uint16_t temp;
// Compute checksum of lower four bits of a byte.
temp = crc16_table[current_crc & 0xF];
current_crc = (current_crc >> 4u) & 0x0FFFu;
current_crc = current_crc ^ temp ^ crc16_table[byte & 0xF];
// Now compute checksum of upper four bits of a byte.
temp = crc16_table[current_crc & 0xF];
current_crc = (current_crc >> 4u) & 0x0FFFu;
current_crc = current_crc ^ temp ^ crc16_table[(byte >> 4u) & 0xF];
return current_crc;
}
uint16_t crc_crc16_update(uint16_t current_crc, const volatile void * p_data, uint32_t size)
{
uint8_t * p_block = (uint8_t *)p_data;
while (size != 0)
{
current_crc = crc16_get(current_crc, *p_block);
p_block++;
size--;
}
return current_crc;
}
/**
* This software is subject to the ANT+ Shared Source License
* www.thisisant.com/swlicenses
* Copyright (c) Dynastream Innovations, Inc. 2012
* 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 Dynastream nor the names of its
* contributors may be used to endorse or promote products
* derived from this software without specific prior
* written permission.
*
* The following actions are prohibited:
* 1) Redistribution of source code containing the ANT+ Network
* Key. The ANT+ Network Key is available to ANT+ Adopters.
* Please refer to http://thisisant.com to become an ANT+
* Adopter and access the key.
*
* 2) Reverse engineering, decompilation, and/or disassembly of
* software provided in binary form under this license.
*
* 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 HEREBY
* 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; DAMAGE TO ANY DEVICE, 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. SOME STATES DO NOT ALLOW
* THE EXCLUSION OF INCIDENTAL OR CONSEQUENTIAL DAMAGES, SO THE
* ABOVE LIMITATIONS MAY NOT APPLY TO YOU.
*
*/
/** @file
* @brief The CRC-16 interface.
* This file is based on implementation originally made by Dynastream Innovations Inc. - August 2012
* @defgroup ant_fs_client_main ANT-FS client device simulator
* @{
* @ingroup ant_fs
*
* @brief The ANT-FS client device simulator.
*
*/
#ifndef CRC_H__
#define CRC_H__
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**@brief Function for calculating CRC-16 in blocks.
*
* Feed each consecutive data block into this function, along with the current value of current_crc
* as returned by the previous call of this function. The first call of this function should pass
* the initial value (usually 0) of the crc in current_crc.
* @param[in] current_crc The current calculated CRC-16 value.
* @param[in] p_data The input data block for computation.
* @param[in] size The size of the input data block in bytes.
*
* @return The updated CRC-16 value, based on the input supplied.
*/
uint16_t crc_crc16_update(uint16_t current_crc, const volatile void * p_data, uint32_t size);
#ifdef __cplusplus
}
#endif
#endif // CRC_H__
/**
*@}
**/
/**
* This software is subject to the ANT+ Shared Source License
* www.thisisant.com/swlicenses
* Copyright (c) Dynastream Innovations, Inc. 2012
* 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 Dynastream nor the names of its
* contributors may be used to endorse or promote products
* derived from this software without specific prior
* written permission.
*
* The following actions are prohibited:
* 1) Redistribution of source code containing the ANT+ Network
* Key. The ANT+ Network Key is available to ANT+ Adopters.
* Please refer to http://thisisant.com to become an ANT+
* Adopter and access the key.
*
* 2) Reverse engineering, decompilation, and/or disassembly of
* software provided in binary form under this license.
*
* 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 HEREBY
* 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; DAMAGE TO ANY DEVICE, 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. SOME STATES DO NOT ALLOW
* THE EXCLUSION OF INCIDENTAL OR CONSEQUENTIAL DAMAGES, SO THE
* ABOVE LIMITATIONS MAY NOT APPLY TO YOU.
*
*/
/**@file
* @brief Definitions.
* This file is based on implementation originally made by Dynastream Innovations Inc. - August 2012
* @defgroup ant_fs_client_main ANT-FS client device simulator
* @{
* @ingroup nrf_ant_fs_client
*
* @brief The ANT-FS client device simulator.
*
*/
#ifndef DEFINES_H__
#define DEFINES_H__
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
#define MAX_ULONG 0xFFFFFFFFu /**< The Max value for the type. */
/**@brief uint16_t type presentation as an union. */
typedef union
{
uint16_t data; /**< The data content. */
struct
{
uint8_t low; /**< The low byte of the data content. */
uint8_t high; /**< The high byte of the data content. */
} bytes;
} ushort_union_t;
/**@brief uint32_t type presentation as an union. */
typedef union
{
uint32_t data; /**< The data content as a single variable. */
uint8_t data_bytes[sizeof(uint32_t)]; /**< The data content as a byte array. */
struct
{
// The least significant byte of the uint32_t in this structure is referenced by byte0.
uint8_t byte0; /**< Byte 0 of the data content. */
uint8_t byte1; /**< Byte 1 of the data content. */
uint8_t byte2; /**< Byte 2 of the data content. */
uint8_t byte3; /**< Byte 3 of the data content. */
} bytes;
} ulong_union_t;
#ifdef __cplusplus
}
#endif
#endif // DEFINES_H__
/**
*@}
**/
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#include "sdk_common.h"
#if NRF_MODULE_ENABLED(ANT_KEY_MANAGER)
#include <stdio.h>
#include "ant_key_manager.h"
#include "ant_key_manager_config.h"
#include "ant_interface.h"
#include "nrf_assert.h"
static uint8_t m_ant_plus_network_key[] = ANT_PLUS_NETWORK_KEY;
static uint8_t m_ant_fs_network_key[] = ANT_FS_NETWORK_KEY;
uint32_t ant_custom_key_set(uint8_t network_number, uint8_t * network_key)
{
ASSERT(network_key != NULL);
return sd_ant_network_address_set(network_number, network_key);
}
uint32_t ant_plus_key_set(uint8_t network_number)
{
return sd_ant_network_address_set(network_number, m_ant_plus_network_key);
}
uint32_t ant_fs_key_set(uint8_t network_number)
{
return sd_ant_network_address_set(network_number, m_ant_fs_network_key);
}
#endif // NRF_MODULE_ENABLED(ANT_KEY_MANAGER)
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#ifndef ANT_KEY_MANAGER_H__
#define ANT_KEY_MANAGER_H__
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @file
*/
/**
* @defgroup ant_key_manager ANT key manager
* @{
* @ingroup ant_sdk_utils
* @brief Module for registering common and custom ANT network keys.
*/
/**@brief Function for registering a custom network key.
*
* @param[in] network_number Network key number.
* @param[in] p_network_key Pointer to the custom ANT network key.
*
* @return A SoftDevice error code.
*/
uint32_t ant_custom_key_set(uint8_t network_number, uint8_t * p_network_key);
/**@brief Function for registering an ANT+ network key.
*
* The key must be defined by @ref ANT_PLUS_NETWORK_KEY.
*
* @note The ANT+ Network Key is available for ANT+ Adopters. Go to http://thisisant.com
* to become an ANT+ Adopter and access the key.
*
* @param[in] network_number Network key number.
*
* @return A SoftDevice error code.
*/
uint32_t ant_plus_key_set(uint8_t network_number);
/**@brief Function for registering an ANT-FS network key.
*
* The key must be defined by @ref ANT_FS_NETWORK_KEY.
*
* @note The ANT+ Network Key is available for ANT+ Adopters. Go to http://thisisant.com
* to become an ANT+ Adopter and access the key.
*
* @param[in] network_number Network key number.
*
* @return A SoftDevice error code.
*/
uint32_t ant_fs_key_set(uint8_t network_number);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif // ANT_KEY_MANAGER_H__
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#ifndef ANT_KEY_MANAGER_CONFIG_H__
#define ANT_KEY_MANAGER_CONFIG_H__
#ifdef __cplusplus
extern "C" {
#endif
/**
* @addtogroup ant_key_manager
* @{
*/
#ifndef ANT_PLUS_NETWORK_KEY
#define ANT_PLUS_NETWORK_KEY {0, 0, 0, 0, 0, 0, 0, 0} /**< The ANT+ network key. */
#endif //ANT_PLUS_NETWORK_KEY
#ifndef ANT_FS_NETWORK_KEY
#define ANT_FS_NETWORK_KEY {0, 0, 0, 0, 0, 0, 0, 0} /**< The ANT-FS network key. */
#endif // ANT_FS_NETWORK_KEY
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif // ANT_KEY_MANAGER_CONFIG_H__
/**
* Copyright (c) 2015 - 2017, Nordic Semiconductor ASA
*
* 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, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, 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 Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA 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.
*
*/
#ifndef ANT_BPWR_LOCAL_H__
#define ANT_BPWR_LOCAL_H__
#include <stdint.h>
#include <stdbool.h>
#include "ant_bpwr.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @addtogroup ant_bpwr
* @{
*/
/** @brief Bicycle Power Sensor control block. */
typedef struct
{
uint8_t message_counter;
ant_bpwr_torque_t torque_use;
enum
{
BPWR_SENS_CALIB_NONE, ///< Idle state.
BPWR_SENS_CALIB_REQUESTED, ///< Received request for general calibration result message by the sensor.
BPWR_SENS_CALIB_READY, ///< Calibration response message is ready to be transmitted.
} calib_stat;
ant_bpwr_calib_handler_t calib_handler;
} ant_bpwr_sens_cb_t;
/**@brief Bicycle Power Sensor RX control block. */
typedef struct
{
uint8_t calib_timeout;
enum
{
BPWR_DISP_CALIB_NONE, ///< Idle state.
BPWR_DISP_CALIB_REQUESTED, ///< Calibration requested.
} calib_stat;
} ant_bpwr_disp_cb_t;
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif // ANT_BPWR_LOCAL_H__
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册