First working NRF5 build copying some random guy's code
This commit is contained in:
parent
8a8f0cf915
commit
872667a425
|
@ -17,6 +17,12 @@ STACK_SIZE := 8192
|
|||
|
||||
SRC_FILES += $(SDK)/modules/nrfx/mdk/gcc_startup_nrf52.S
|
||||
SRC_FILES += $(SDK)/modules/nrfx/mdk/system_nrf52.c
|
||||
SRC_FILES += $(SDK)/modules/nrfx/drivers/src/nrfx_systick.c
|
||||
SRC_FILES += $(SDK)/modules/nrfx/drivers/src/nrfx_uart.c
|
||||
SRC_FILES += $(SDK)/modules/nrfx/drivers/src/prs/nrfx_prs.c
|
||||
SRC_FILES += $(SDK)/components/libraries/util/app_util_platform.c
|
||||
SRC_FILES += $(SDK)/external/fprintf/nrf_fprintf.c
|
||||
SRC_FILES += $(SDK)/external/fprintf/nrf_fprintf_format.c
|
||||
SRC_FILES += $(PROJ)/main.c
|
||||
|
||||
SRC_DIRS := $(dir $(SRC_FILES))
|
||||
|
@ -24,9 +30,10 @@ SRCES := $(notdir $(SRC_FILES))
|
|||
OBJECTS := $(SRCES:=.o)
|
||||
OBJ_FILES := $(addprefix $(BUILD_DIR)/,$(OBJECTS))
|
||||
|
||||
INC_FOLDERS += $(PROJ)
|
||||
INC_FOLDERS += $(PROJ)
|
||||
INC_FOLDERS += $(SDK)/modules/nrfx $(SDK)/modules/nrfx/mdk
|
||||
INC_FOLDERS += $(SDK)/modules/nrfx/hal
|
||||
INC_FOLDERS += $(SDK)/modules/nrfx $(SDK)/modules/nrfx/mdk
|
||||
INC_FOLDERS += $(SDK)/modules/nrfx/hal $(SDK)/modules/nrfx/drivers/include
|
||||
INC_FOLDERS += $(SDK)/components/libraries/strerror $(SDK)/components/toolchain/cmsis/include
|
||||
INC_FOLDERS += $(SDK)/components/libraries/util $(SDK)/components/libraries/balloc
|
||||
INC_FOLDERS += $(SDK)/components/libraries/ringbuf $(SDK)/components/libraries/bsp
|
||||
|
@ -35,6 +42,7 @@ INC_FOLDERS += $(SDK)/components/libraries/delay $(SDK)/components/drive
|
|||
INC_FOLDERS += $(SDK)/components/libraries/atomic $(SDK)/components/boards
|
||||
INC_FOLDERS += $(SDK)/components/libraries/memobj $(SDK)/components/libraries/log/src
|
||||
INC_FOLDERS += $(SDK)/external/fprintf $(SDK)/integration/nrfx
|
||||
INC_FOLDERS += $(SDK)/integration/nrfx/legacy
|
||||
|
||||
CFLAGS += -std=c99 -MP -MD -c -g3 $(OPTIMISE)
|
||||
CFLAGS += -DBOARD_CUSTOM -DBSP_DEFINES_ONLY -DCONFIG_GPIO_AS_PINRESET -DFLOAT_ABI_HARD -DNRF52 -DNRF52832_XXAA -DNRF52_PAN_74
|
||||
|
|
177
fw/nrf52/main.c
177
fw/nrf52/main.c
|
@ -1,14 +1,173 @@
|
|||
// LED blink and serial interface on nRF52832 breakout board
|
||||
// See iosoft.blog for details
|
||||
|
||||
#include <stdarg.h>
|
||||
#include "nrf_gpio.h"
|
||||
#include "nrf_delay.h"
|
||||
#include "nrf_drv_systick.h"
|
||||
#include "nrfx_uart.h"
|
||||
#include "nrf_fprintf.h"
|
||||
|
||||
// LED definitions
|
||||
#define LED_PIN 7
|
||||
#define LED_BIT (1 << LED_PIN)
|
||||
#define LED_PIN 7
|
||||
#define LED_BIT (1 << LED_PIN)
|
||||
|
||||
int main(void) {
|
||||
nrf_gpio_cfg_output(LED_PIN);
|
||||
while (1) {
|
||||
nrf_delay_ms(500);
|
||||
NRF_GPIO->OUT ^= LED_BIT;
|
||||
}
|
||||
// UART definitions
|
||||
#define UART_PIN_DISCONNECTED 0xFFFFFFFF
|
||||
#define UART_TX_PIN 15
|
||||
#define UART_RX_PIN 14
|
||||
#define UART_RTS_PIN UART_PIN_DISCONNECTED
|
||||
#define UART_CTS_PIN UART_PIN_DISCONNECTED
|
||||
#define UART_BAUD NRF_UART_BAUDRATE_115200
|
||||
#define UART_BUFF_SIZE 1024
|
||||
#define PRINTF_BUFF_SIZE 1024
|
||||
#define SER_TX_BUFFLEN 1500
|
||||
|
||||
uint32_t msticks, systicks;
|
||||
char printf_buff[PRINTF_BUFF_SIZE];
|
||||
|
||||
// Circular buffer for serial Tx
|
||||
int ser_txin=0, ser_txout=0;
|
||||
uint8_t ser_txbuff[SER_TX_BUFFLEN];
|
||||
|
||||
void init_gpio(void);
|
||||
int mstimeout(uint32_t *tickp, uint32_t msec);
|
||||
void init_serial(void);
|
||||
void poll_serial(void);
|
||||
int putch(int c);
|
||||
void uart_event_handler(nrfx_uart_event_t const * evtp, void *ctxp);
|
||||
void uart_tx(void const *ctxt, char const *buff, size_t len);
|
||||
|
||||
// Context for printf function
|
||||
nrf_fprintf_ctx_t fprintf_ctx =
|
||||
{
|
||||
.p_io_buffer=printf_buff, .io_buffer_size=PRINTF_BUFF_SIZE,
|
||||
.fwrite = uart_tx
|
||||
};
|
||||
|
||||
// Context for UART 0
|
||||
nrfx_uart_t nrfx_uart =
|
||||
{
|
||||
NRF_UART0, 0
|
||||
};
|
||||
|
||||
int main(void)
|
||||
{
|
||||
uint32_t tix;
|
||||
|
||||
mstimeout(&tix, 0);
|
||||
init_gpio();
|
||||
init_serial();
|
||||
printf("\nNRF52 test\n");
|
||||
while (1)
|
||||
{
|
||||
if (mstimeout(&tix, 500))
|
||||
{
|
||||
NRF_GPIO->OUT ^= LED_BIT;
|
||||
putch('.');
|
||||
}
|
||||
poll_serial();
|
||||
}
|
||||
}
|
||||
|
||||
// Initialise I/O port, and system tick counter
|
||||
void init_gpio(void)
|
||||
{
|
||||
nrf_gpio_cfg_output(LED_PIN);
|
||||
nrf_drv_systick_init();
|
||||
}
|
||||
|
||||
// Check for timeout in milliseconds
|
||||
int mstimeout(uint32_t *tickp, uint32_t msec)
|
||||
{
|
||||
uint32_t t, diff;
|
||||
|
||||
t = nrf_systick_val_get();
|
||||
diff = NRF_SYSTICK_VAL_MASK & (systicks - t);
|
||||
|
||||
if (msec == 0)
|
||||
{
|
||||
systicks = t;
|
||||
*tickp = msticks;
|
||||
}
|
||||
else if ((diff /= SystemCoreClock/1000) > 0)
|
||||
{
|
||||
systicks = t;
|
||||
msticks += diff;
|
||||
diff = msticks - *tickp;
|
||||
if (diff >= msec)
|
||||
{
|
||||
*tickp = msticks;
|
||||
return(1);
|
||||
}
|
||||
}
|
||||
return(0);
|
||||
}
|
||||
|
||||
// Formatted print to serial port
|
||||
int printf(const char *fmt, ...)
|
||||
{
|
||||
va_list args;
|
||||
int n;
|
||||
|
||||
va_start(args, fmt);
|
||||
nrf_fprintf(&fprintf_ctx, fmt, &args);
|
||||
n = fprintf_ctx.io_buffer_cnt;
|
||||
nrf_fprintf_buffer_flush(&fprintf_ctx);
|
||||
va_end(args);
|
||||
return(n);
|
||||
}
|
||||
|
||||
// Initialise serial I/O
|
||||
void init_serial(void)
|
||||
{
|
||||
const nrfx_uart_config_t config = {
|
||||
UART_TX_PIN, UART_RX_PIN,
|
||||
UART_CTS_PIN, UART_RTS_PIN, 0,
|
||||
NRF_UART_HWFC_DISABLED, 0, UART_BAUD,
|
||||
APP_IRQ_PRIORITY_LOWEST};
|
||||
nrfx_uart_init(&nrfx_uart, &config, 0);
|
||||
}
|
||||
|
||||
// Poll serial interface, send next Tx char
|
||||
void poll_serial(void)
|
||||
{
|
||||
uint8_t b;
|
||||
|
||||
if (ser_txin!=ser_txout && !nrfx_uart_tx_in_progress(&nrfx_uart))
|
||||
{
|
||||
b = ser_txbuff[ser_txout++];
|
||||
if (ser_txout >= SER_TX_BUFFLEN)
|
||||
ser_txout = 0;
|
||||
nrfx_uart_tx(&nrfx_uart, &b, 1);
|
||||
}
|
||||
}
|
||||
|
||||
// Add character to serial Tx circular buffer
|
||||
// Discard character if buffer is full
|
||||
int putch(int c)
|
||||
{
|
||||
int in=ser_txin+1;
|
||||
|
||||
if (in >= SER_TX_BUFFLEN)
|
||||
in = 0;
|
||||
if (in != ser_txout)
|
||||
{
|
||||
ser_txbuff[ser_txin] = (uint8_t)c;
|
||||
ser_txin = in;
|
||||
}
|
||||
return(c);
|
||||
}
|
||||
|
||||
// Send data block to UART (via circular buffer)
|
||||
void uart_tx(void const *ctxp, char const *buff, size_t len)
|
||||
{
|
||||
while (len--)
|
||||
putch(*buff++);
|
||||
}
|
||||
|
||||
// Dummy UART event handler
|
||||
void uart_event_handler(nrfx_uart_event_t const * evtp, void *ctxp)
|
||||
{
|
||||
}
|
||||
|
||||
// EOF
|
||||
|
|
|
@ -0,0 +1,64 @@
|
|||
/* Linker script to configure memory regions. */
|
||||
|
||||
SEARCH_DIR(.)
|
||||
GROUP(-lgcc -lc -lnosys)
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x0, LENGTH = 0x80000
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x10000
|
||||
}
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
}
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
. = ALIGN(4);
|
||||
.mem_section_dummy_ram :
|
||||
{
|
||||
}
|
||||
.log_dynamic_data :
|
||||
{
|
||||
PROVIDE(__start_log_dynamic_data = .);
|
||||
KEEP(*(SORT(.log_dynamic_data*)))
|
||||
PROVIDE(__stop_log_dynamic_data = .);
|
||||
} > RAM
|
||||
.log_filter_data :
|
||||
{
|
||||
PROVIDE(__start_log_filter_data = .);
|
||||
KEEP(*(SORT(.log_filter_data*)))
|
||||
PROVIDE(__stop_log_filter_data = .);
|
||||
} > RAM
|
||||
|
||||
} INSERT AFTER .data;
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.mem_section_dummy_rom :
|
||||
{
|
||||
}
|
||||
.log_const_data :
|
||||
{
|
||||
PROVIDE(__start_log_const_data = .);
|
||||
KEEP(*(SORT(.log_const_data*)))
|
||||
PROVIDE(__stop_log_const_data = .);
|
||||
} > FLASH
|
||||
.log_backends :
|
||||
{
|
||||
PROVIDE(__start_log_backends = .);
|
||||
KEEP(*(SORT(.log_backends*)))
|
||||
PROVIDE(__stop_log_backends = .);
|
||||
} > FLASH
|
||||
.nrf_balloc :
|
||||
{
|
||||
PROVIDE(__start_nrf_balloc = .);
|
||||
KEEP(*(.nrf_balloc))
|
||||
PROVIDE(__stop_nrf_balloc = .);
|
||||
} > FLASH
|
||||
|
||||
} INSERT AFTER .text
|
||||
|
||||
|
||||
INCLUDE "nrf_common.ld"
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_ATOMIC_H_INCLUDED
|
||||
#define HAL_ATOMIC_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the Atomic section routines and necessary types.
|
||||
*
|
||||
* @defgroup hal_atomic HAL Atomic API
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL Atomic API
|
||||
* @details The Atomic module implements atomic section interface. This is made by disabling the global interrupts,
|
||||
* which is a hardware dependent feature. The user may call hal_atomic_start() to open an atomic section
|
||||
* (disable interrupts) and hal_atomic_end() to exit from the section (restore interrupts). The algorithm
|
||||
* supports nesting sections.
|
||||
*/
|
||||
|
||||
typedef volatile uint32_t atomic_t;
|
||||
|
||||
|
||||
/**@brief Enters atomic section.
|
||||
*
|
||||
* @details Disables global interrupts.
|
||||
*
|
||||
* @param[in] p_atomic pointer to buffer to store current value of the status register.
|
||||
*/
|
||||
void hal_atomic_start(atomic_t * p_atomic);
|
||||
|
||||
/**
|
||||
* @brief Exits atomic section
|
||||
*
|
||||
* @details Restores status register
|
||||
*
|
||||
* @param[in] p_atomic pointer to buffer to restore current value of the status register from.
|
||||
*/
|
||||
void hal_atomic_end(atomic_t * p_atomic);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // HAL_ATOMIC_H_INCLUDED
|
|
@ -0,0 +1,59 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_CLOCK_H_INCLUDED
|
||||
#define HAL_CLOCK_H_INCLUDED
|
||||
|
||||
/**
|
||||
* @defgroup hal_clock HAL Clock API
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL Clock library
|
||||
*/
|
||||
|
||||
/** @brief This function performs initialization and configuration of processor's
|
||||
* clock module.
|
||||
*/
|
||||
void hal_clock_init(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_CLOCK_H_INCLUDED */
|
|
@ -0,0 +1,113 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_DEBUG_INTERFACE_H_INCLUDED
|
||||
#define HAL_DEBUG_INTERFACE_H_INCLUDED
|
||||
|
||||
|
||||
#if defined(NRF52) || defined(NRF52840_XXAA)
|
||||
|
||||
#include "nrf_assert.h"
|
||||
|
||||
#endif // NRF52
|
||||
|
||||
/**
|
||||
* @defgroup hal_debug_interface HAL Debug Interface
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL debug interface
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_DEBUG
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define HAL_DEBUG_INTERFACE_INIT() hal_debug_init()
|
||||
#define HAL_DEBUG_INTERFACE_PUT(c, n) hal_debug_put(c, n)
|
||||
#define HAL_DEBUG_INTERFACE_PUTC(c) hal_debug_putc(c)
|
||||
#define HAL_DEBUG_INTERFACE_PUTS(s) hal_debug_puts(s)
|
||||
|
||||
/**
|
||||
* @brief Debug interface initialization
|
||||
*/
|
||||
void hal_debug_init(void);
|
||||
|
||||
/**
|
||||
* @brief Sends string to the debug interface
|
||||
*
|
||||
* @details send debug data using debug interface
|
||||
*
|
||||
* @param[in] p_data debug string.
|
||||
* @param[in] len string length.
|
||||
*/
|
||||
void hal_debug_put(const void * p_data, uint8_t len);
|
||||
|
||||
/**
|
||||
* @brief Sends char symbol to the debug interface
|
||||
*
|
||||
* @details send debug data using debug interface
|
||||
*
|
||||
* @param[in] data char symbol.
|
||||
*/
|
||||
void hal_debug_putc(const char data);
|
||||
|
||||
/**
|
||||
* @brief Sends a null-terminated string to the debug interface
|
||||
*
|
||||
* @details send debug data using debug interface
|
||||
*
|
||||
* @param[in] p_data null-terminated string.
|
||||
*/
|
||||
void hal_debug_puts(const char * p_data);
|
||||
|
||||
#else
|
||||
|
||||
/* If debug is disabled, these macros are just a stub.*/
|
||||
#define HAL_DEBUG_INTERFACE_INIT()
|
||||
#define HAL_DEBUG_INTERFACE_PUT(c, n)
|
||||
#define HAL_DEBUG_INTERFACE_PUTC(c)
|
||||
#define HAL_DEBUG_INTERFACE_PUTS(s)
|
||||
|
||||
#endif // CONFIG_DEBUG
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // HAL_DEBUG_INTERFACE_H_INCLUDED
|
|
@ -0,0 +1,65 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_DELAY_H_INCLUDED
|
||||
#define HAL_DELAY_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declaration of the Hardware Delay routine.
|
||||
*
|
||||
* @defgroup hal_delay HAL Delay API
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL Delay API
|
||||
* @details The Delay module implements the only hal_delay() routine to delay the execution for some microseconds.
|
||||
*/
|
||||
|
||||
/**@brief Function for delaying execution for number of microseconds.
|
||||
*
|
||||
* @param[in] number_of_us number of microseconds to delay.
|
||||
*/
|
||||
void hal_delay(uint32_t number_of_us);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // HAL_DELAY_H_INCLUDED
|
|
@ -0,0 +1,54 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_LED_H_INCLUDED
|
||||
#define HAL_LED_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define HAL_LED_AMOUNT 4
|
||||
|
||||
void hal_led_init(uint32_t led_mask);
|
||||
void hal_led_on(uint32_t led_mask);
|
||||
void hal_led_off(uint32_t led_mask);
|
||||
void hal_led_toggle(uint32_t led_mask);
|
||||
|
||||
#endif /* HAL_LED_H_INCLUDED */
|
|
@ -0,0 +1,89 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_MUTEX_H_INCLUDED
|
||||
#define HAL_MUTEX_H_INCLUDED
|
||||
|
||||
#include "hal_atomic.h"
|
||||
|
||||
/** @file
|
||||
* This is a simple mutex interface to be used in System Memory Manager
|
||||
* to make it thread aware.
|
||||
*
|
||||
* @defgroup hal_mutex HAL Mutex API
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @details NRF52 implementation is void and PC implementation is identical to atomic.
|
||||
*/
|
||||
|
||||
|
||||
#if defined ( __GNUC__ )
|
||||
#include <signal.h>
|
||||
typedef volatile sig_atomic_t mutex_t;
|
||||
#else
|
||||
#include <stdint.h>
|
||||
typedef volatile uint32_t mutex_t;
|
||||
#endif
|
||||
|
||||
|
||||
/**@brief Configures mutex lock before first usage.
|
||||
*
|
||||
* @param[inout] p_mutex pointer to mutex variable.
|
||||
*/
|
||||
void hal_mutex_init(mutex_t * p_mutex);
|
||||
|
||||
/**@brief Atomically sets mutex. If set is failed, enters spin lock loop.
|
||||
*
|
||||
* @param[in] p_mutex pointer to mutex variable.
|
||||
*/
|
||||
void hal_mutex_lock(mutex_t * p_mutex);
|
||||
|
||||
/**
|
||||
* @brief Atomically clears mutex. Every other thread, spinning at this lock may
|
||||
* try to lock it afterwards.
|
||||
*
|
||||
* @param[in] p_mutex pointer to mutex variable.
|
||||
*/
|
||||
void hal_mutex_unlock(mutex_t * p_mutex);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_MUTEX_H_INCLUDED */
|
|
@ -0,0 +1,70 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_RNG_H_INCLUDED
|
||||
#define HAL_RNG_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declaration of the random number generator routine.
|
||||
*
|
||||
* @defgroup hal_rng HAL Random Number Generator API
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL Random Number Generator API
|
||||
* @details The Random number generator module implements the only hal_rand_get() routine to get an unsigned 8-bits
|
||||
* random number generated by hardware.
|
||||
*/
|
||||
|
||||
/**@brief Initialize hardware random generator.
|
||||
*/
|
||||
extern void hal_rand_init(void);
|
||||
|
||||
/**@brief Generates random number using hardware.
|
||||
*
|
||||
* @return An unsigned 8-bits random number.
|
||||
*/
|
||||
extern uint8_t hal_rand_get(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_RNG_H_INCLUDED */
|
|
@ -0,0 +1,100 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_SLEEP_H_INCLUDED
|
||||
#define HAL_SLEEP_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declaration of the HAL sleep interface.
|
||||
*
|
||||
* @defgroup hal_sleep HAL Sleep API
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL Sleep API
|
||||
* @details The Sleep module implements the only hal_sleep() routine to put the hardware to the sleep mode for some
|
||||
* milliseconds. The user can use convenient macros DAYS_TO_MS(), HOURS_TO_MS(), MINS_TO_MS(), and SEC_TO_MS()
|
||||
* to convert different time periods into milliseconds. Please note that this module requires a call to
|
||||
* hal_sleep_init() which is in turn called by sys_init() before using any module routines. This module is
|
||||
* only used to implement the System Sleep interface. The hal_sleep() routine is not assumed to be used by
|
||||
* the user explicitly.
|
||||
*/
|
||||
|
||||
/**@brief Converts days to milliseconds */
|
||||
#define DAYS_TO_MS(d) ((d) * 3600L * 24L * 1000L )
|
||||
|
||||
/**@brief Converts hours to milliseconds */
|
||||
#define HOURS_TO_MS(h) ((h) * 3600L * 1000L )
|
||||
|
||||
/**@brief Converts minutes to milliseconds */
|
||||
#define MINS_TO_MS(m) ((m) * 60L * 1000L )
|
||||
|
||||
/**@brief Converts seconds to milliseconds */
|
||||
#define SEC_TO_MS(s) ((s) * 1000L )
|
||||
|
||||
/**@brief Information, provided by the HAL, in order to explain the reason,
|
||||
* which caused the system to wake up.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
UNKNOWN_INTERRUPT, /**< HAL can't define a wake up reason */
|
||||
RTC_CC_INTERRUPT /**< RTC interrupt was the awakening reason */
|
||||
} hal_wakeup_reason_t;
|
||||
|
||||
|
||||
/**@brief Puts hardware into the sleep mode for some milliseconds.
|
||||
*
|
||||
* @param[in] sleep_time_ms Time to sleep in ms
|
||||
*
|
||||
* @retval wakeup_reason Specifies reason of awakening
|
||||
*/
|
||||
hal_wakeup_reason_t hal_sleep(uint32_t sleep_time_ms);
|
||||
|
||||
|
||||
/**@brief Initialization of the sleep module
|
||||
*
|
||||
*/
|
||||
void hal_sleep_init(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_SLEEP_H_INCLUDED */
|
|
@ -0,0 +1,124 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_TASK_H_INCLUDED
|
||||
#define HAL_TASK_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "hal_atomic.h"
|
||||
#include "sys_utils.h"
|
||||
#include "sys_task_scheduler.h"
|
||||
|
||||
/**
|
||||
* @defgroup hal_task HAL Tasks
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL tasks library
|
||||
*/
|
||||
|
||||
/**@brief Identifiers for registered HAL handlers.
|
||||
*
|
||||
* @details enumeration with identifiers of registered HAL handlers.
|
||||
* HAL handlers will be called from the HAL task.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
HAL_TIMER_TASK_ID,
|
||||
HAL_UART_TASK_ID,
|
||||
HAL_TIMER_CRITICAL_MANUAL_TASK,
|
||||
HAL_TASKS_AMOUNT,
|
||||
} hal_task_id_t;
|
||||
|
||||
|
||||
/**@brief Prototype of a HAL task handler.
|
||||
*
|
||||
* @details Handler which will be called from HAL task.
|
||||
*/
|
||||
typedef void (* hal_task_handler_t)(void);
|
||||
|
||||
|
||||
void hal_task_handler(void);
|
||||
void hal_timer_task_handler(void);
|
||||
void hal_uart_task_handler(void);
|
||||
void hal_timer_critical_manual_handler(void);
|
||||
|
||||
/**@brief Pending HAL tasks.
|
||||
*
|
||||
* @details Variable which includes markers of pending HAL tasks.
|
||||
*/
|
||||
extern volatile uint_fast16_t g_hal_tasks;
|
||||
|
||||
|
||||
/**@brief Notify task scheduler to add a HAL task for execution.
|
||||
*
|
||||
* @details The function sets a marker for the HAL task for execution.
|
||||
*
|
||||
* @param[in] hal_task_id HAL task identifier (see \ref hal_task_id_t enumeration).
|
||||
*/
|
||||
static inline void hal_task_post(hal_task_id_t hal_task_id)
|
||||
{
|
||||
atomic_t atomic = 0;
|
||||
|
||||
hal_atomic_start(&atomic);
|
||||
g_hal_tasks |= BIT(hal_task_id);
|
||||
hal_atomic_end(&atomic);
|
||||
|
||||
sys_task_post(HAL_TASK_ID);
|
||||
}
|
||||
|
||||
/**@brief Removes a task from pending list in HAL task scheduler.
|
||||
*
|
||||
* @details The function removes a marker from the HAL execution list.
|
||||
*
|
||||
* @param[in] hal_task_id HAL task identifier (see \ref hal_task_id_t enumeration).
|
||||
*/
|
||||
static inline void hal_task_unpost(hal_task_id_t hal_task_id)
|
||||
{
|
||||
atomic_t atomic = 0;
|
||||
|
||||
hal_atomic_start(&atomic);
|
||||
g_hal_tasks &= ~BIT(hal_task_id);
|
||||
hal_atomic_end(&atomic);
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // HAL_TASK_H_INCLUDED
|
|
@ -0,0 +1,80 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_TIMER_H_INCLUDED
|
||||
#define HAL_TIMER_H_INCLUDED
|
||||
|
||||
#include "hal_delay.h"
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* @defgroup hal_timer HAL Timer
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL timer interface
|
||||
*/
|
||||
|
||||
/**@brief Initializes hardware timer.
|
||||
*/
|
||||
void hal_timer_init(void);
|
||||
|
||||
|
||||
/**@brief Starts hardware timer.
|
||||
*
|
||||
* @param[in] interval timer interval in microseconds for timer start.
|
||||
*/
|
||||
void hal_timer_start(uint64_t interval);
|
||||
|
||||
|
||||
/**@brief Stops hardware timer.
|
||||
*/
|
||||
void hal_timer_stop(void);
|
||||
|
||||
|
||||
/**@brief Reads microseconds passed since the device start.
|
||||
*
|
||||
* @return time in microseconds since the device was launched.
|
||||
*/
|
||||
uint64_t hal_time_get(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_TIMER_H_INCLUDED */
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_TIMER_CRITICAL_H_INCLUDED
|
||||
#define HAL_TIMER_CRITICAL_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
/**
|
||||
* @defgroup hal_timer_critical HAL Hardware Critical Timer
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL hardware critical timer interface
|
||||
*/
|
||||
|
||||
/**@brief Prototype for critical timer handler.
|
||||
*/
|
||||
typedef void (* hal_timer_critical_handler_t)(void);
|
||||
|
||||
|
||||
/**@brief Starts hardware critical timer.
|
||||
*
|
||||
* @param[in] interval_us timer interval for timer start.
|
||||
* @param[in] handler critical timer event handler.
|
||||
*/
|
||||
void hal_timer_critical_start(uint32_t interval_us, hal_timer_critical_handler_t handler);
|
||||
|
||||
|
||||
/**@brief Stops hardware critical timer.
|
||||
*/
|
||||
void hal_timer_critical_stop(void);
|
||||
|
||||
|
||||
/**@brief Check if critical timer is currently used.
|
||||
*
|
||||
* @retval timer_state true - timer is running now
|
||||
* false - timer in stop mode
|
||||
*/
|
||||
bool is_critical_timer_started(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_TIMER_CRITICAL_H_INCLUDED */
|
|
@ -0,0 +1,103 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_TRACE_INTERFACE_H_INCLUDED
|
||||
#define HAL_TRACE_INTERFACE_H_INCLUDED
|
||||
|
||||
/**
|
||||
* @defgroup hal_trace_interface HAL Trace Interface
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL Trace Interface
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_TRACE
|
||||
|
||||
#include "hal_uart.h"
|
||||
|
||||
|
||||
#define HAL_TRACE_INTERFACE_REUSE(p_uart_desc) hal_trace_reuse(p_uart_desc)
|
||||
#define HAL_TRACE_INTERFACE_INIT() hal_trace_init()
|
||||
#define HAL_TRACE_INTERFACE_PUTS(s) hal_trace_puts(s)
|
||||
#define HAL_TRACE_INTERFACE_FINALIZE() hal_trace_finalize()
|
||||
|
||||
/**
|
||||
* @brief Trace interface initialization
|
||||
*/
|
||||
void hal_trace_init(void);
|
||||
|
||||
/**
|
||||
* @brief Initializes trace interface, using already initialized UART.
|
||||
*
|
||||
* @param[in] p_uart_desc UART descriptor, which has been already initialized.
|
||||
*/
|
||||
void hal_trace_reuse(hal_uart_descriptor_t * p_uart_desc);
|
||||
|
||||
/**
|
||||
* @brief Sends a null-terminated string to the debug interface
|
||||
*
|
||||
* @details send debug data using debug interface
|
||||
*
|
||||
* @param[in] p_data null-terminated string.
|
||||
*/
|
||||
void hal_trace_puts(const char * p_data);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Finalizes buffered trace data output to UART,
|
||||
* before commencing non-buffered assertion output
|
||||
*/
|
||||
void hal_trace_finalize(void);
|
||||
|
||||
|
||||
#else
|
||||
|
||||
/* If debug is disabled, these macros are just a stub.*/
|
||||
#define HAL_TRACE_INTERFACE_REUSE(p_uart_desc)
|
||||
#define HAL_TRACE_INTERFACE_INIT()
|
||||
#define HAL_TRACE_INTERFACE_PUTS(s)
|
||||
#define HAL_TRACE_INTERFACE_FINALIZE()
|
||||
|
||||
#endif // CONFIG_DEBUG
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // HAL_TRACE_INTERFACE_H_INCLUDED
|
|
@ -0,0 +1,284 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_UART_H_INCLUDED
|
||||
#define HAL_UART_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <limits.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the routines, types and macros to implement the UART protocol.
|
||||
*
|
||||
* @defgroup hal_uart HAL UART protocol
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL UART protocol
|
||||
* @details The UART module implements the standard UART driver API. This includes open/close via hal_uart_open(),
|
||||
* hal_uart_close(), read/write via hal_uart_read(), hal_uart_write() routines, and hal_uart_puts() for
|
||||
* sending a null-terminated string in a non-blocking way. The user also can get some info about the available
|
||||
* bytes for read/write via hal_uart_read_buffer_size_get() and hal_uart_write_buffer_size_get(). This implies
|
||||
* that the user may register read/write buffers to use for buffered input/output and handler routines that
|
||||
* will be called upon read/written characters. Also the most popular settings of the UART driver are supported:
|
||||
* different baudrates, parity checks, flow control, character size, and stop bits.
|
||||
*/
|
||||
|
||||
/** @brief Maximum size in bytes of input and output buffers. */
|
||||
#define MAX_QUEUE_LENGTH 0xffffu
|
||||
|
||||
/** @brief Maximum size in bytes of data can be stored in hardware unit output buffer. */
|
||||
#define MAX_TX_CHUNK_SIZE UCHAR_MAX
|
||||
|
||||
/** @brief UART baudrate. */
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_BAUDRATE_38400, /**< 38400 bits per second.*/
|
||||
HAL_UART_BAUDRATE_115200, /**< 115200 bits per second.*/
|
||||
HAL_UART_BAUDRATE_230400 /**< 230400 bits per second.*/
|
||||
} hal_uart_baudrate_t;
|
||||
|
||||
/** @brief UART parity check. */
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_PARITY_NONE, /**< Do not check parity.*/
|
||||
HAL_UART_PARITY_EVEN /**< Check even parity.*/
|
||||
} hal_uart_parity_t;
|
||||
|
||||
/** @brief UART flow control. */
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_FLOW_CONTROL_DISABLED, /**< Flow control is disabled.*/
|
||||
HAL_UART_FLOW_CONTROL_ENABLED, /**< Flow control is enabled.*/
|
||||
} hal_uart_flow_control_t;
|
||||
|
||||
/** @brief UART character size settings. */
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_FIVE_BITS_CHAR = 5, /**< 5 bits character.*/
|
||||
HAL_UART_SIX_BITS_CHAR, /**< 6 bits character.*/
|
||||
HAL_UART_SEVEN_BITS_CHAR, /**< 7 bits character.*/
|
||||
HAL_UART_EIGHT_BITS_CHAR, /**< 8 bits character.*/
|
||||
} hal_uart_char_size_t;
|
||||
|
||||
/** @brief UART stop bits settings. */
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_ONE_STOP_BIT, /**< 1 stop bit.*/
|
||||
HAL_UART_ONEHALF_STOP_BITS, /**< 1.5 stop bits.*/
|
||||
HAL_UART_TWO_STOP_BITS, /**< 2 stop bits.*/
|
||||
} hal_uart_stop_bits_t;
|
||||
|
||||
/** @brief Represents error source for the UART driver. There might be other values,
|
||||
* representing clearer elaborating of error statuses, if this module is used
|
||||
* with Windows or Linux.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_ERROR_NONE = 0, /**< Success.*/
|
||||
HAL_UART_ERROR_TX_OVERFLOW = 252, /**< This error happens when amount of elements in
|
||||
the transmitter ring buffer exceeds its size.
|
||||
All the data above limit is not placed into
|
||||
buffer.*/
|
||||
HAL_UART_ERROR_RX_OVERFLOW = 253, /**< This error happens when amount of elements in
|
||||
the receiver ring buffer exceeds its size.
|
||||
All the unread data is overwritten with new
|
||||
received data.*/
|
||||
HAL_UART_ERROR_RX_UNDERFLOW = 254, /**< This error happens when the user-side software
|
||||
tries to read more elements than it is available
|
||||
in the receive buffer.
|
||||
The user-side buffer will be filled with all available
|
||||
characters and then the error handler is started.*/
|
||||
HAL_UART_ERROR_HW_ERROR = 255, /**< There is some unrecoverable error in hardware.*/
|
||||
} hal_uart_error_t;
|
||||
|
||||
/**
|
||||
* @brief User-side handler of UART read and write events.
|
||||
*
|
||||
* @param[in] channel event channel number.
|
||||
* @param[in] char_count number of characters successfully sent before entering
|
||||
* the callback function.
|
||||
*/
|
||||
typedef void (*hal_uart_handler_t)(uint32_t channel, size_t char_count);
|
||||
|
||||
/**
|
||||
* @brief User-side handler for UART error events.
|
||||
*
|
||||
* @param[in] channel event channel number.
|
||||
* @param[in] error_id call reason.
|
||||
*/
|
||||
typedef void (*hal_uart_error_handler_t)(uint32_t channel, hal_uart_error_t error_id);
|
||||
|
||||
/** @brief HAL UART configuration structure.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t module; /**< UART module number. By now zero
|
||||
is the only option.*/
|
||||
uint32_t tx_pin; /**< Number of pin used as TX.*/
|
||||
uint32_t rx_pin; /**< Number of pin used as RX.*/
|
||||
uint32_t cts_pin; /**< Number of pin used as CTS.*/
|
||||
uint32_t rts_pin; /**< Number of pin used as RTS.*/
|
||||
hal_uart_baudrate_t baudrate; /**< Baudrate selector.*/
|
||||
hal_uart_parity_t parity; /**< Parity selector.*/
|
||||
hal_uart_flow_control_t flow_control; /**< Flow control selector.*/
|
||||
hal_uart_char_size_t char_size; /**< Size of char in bits.*/
|
||||
hal_uart_stop_bits_t stop_bits; /**< Stop bits number.*/
|
||||
} hal_uart_config_t;
|
||||
|
||||
/**
|
||||
* @brief This structure defines the UART module operation.
|
||||
*
|
||||
* If \a write_buffer_ptr is defined as NULL, then sending data will work
|
||||
* in blocking way, that is call for \a hal_uart_write will be completed
|
||||
* only after sending of the last byte passed as input parameter.
|
||||
*
|
||||
* If \a read_buffer_ptr is defined as NULL, then driver will drop every
|
||||
* received byte.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
hal_uart_config_t uart_config; /**< UART settings struct.*/
|
||||
hal_uart_handler_t write_handler; /**< Callback function for write operation.*/
|
||||
void * write_buffer_ptr; /**< User-side buffer for write operation.*/
|
||||
size_t write_buffer_size; /**< Size of write operation buffer.*/
|
||||
hal_uart_handler_t read_handler; /**< Callback function for read operation.*/
|
||||
void * read_buffer_ptr; /**< User-side buffer for read operation.*/
|
||||
size_t read_buffer_size; /**< Size of read operation buffer.*/
|
||||
hal_uart_error_handler_t error_handler; /**< Callback function in case of something
|
||||
goes wrong.*/
|
||||
} hal_uart_descriptor_t;
|
||||
|
||||
/**
|
||||
* @brief Configures UART interface using input parameter.
|
||||
*
|
||||
* @param[in] config pointer to a config struct.
|
||||
* @param[in] descriptor pointer to a descriptor struct.
|
||||
*
|
||||
* @return Return status of operation.
|
||||
*/
|
||||
hal_uart_error_t hal_uart_open(const hal_uart_config_t * config,
|
||||
const hal_uart_descriptor_t * descriptor);
|
||||
|
||||
/**
|
||||
* @brief Sends data in a non-blocking way.
|
||||
*
|
||||
* @param[in] descriptor pointer to the UART module operation structure.
|
||||
* @param[in] data pointer to the user-side buffer of output data.
|
||||
* @param[in] length number of bytes to transmit.
|
||||
*
|
||||
* If descriptor has a non-null \a write_buffer_ptr then this function will use it
|
||||
* as a temporary buffer and will copy input \a data to it before starting
|
||||
* transmit. If descriptor has the NULL \a write_buffer_ptr, then the user-side code
|
||||
* is responsible to retain \a data until \a write_handler is called.
|
||||
*/
|
||||
void hal_uart_write(const hal_uart_descriptor_t * descriptor,
|
||||
const uint8_t * data,
|
||||
const size_t length);
|
||||
|
||||
/**
|
||||
* @brief Sends a null-terminated C-string in a non-blocking way.
|
||||
*
|
||||
* @param[in] descriptor pointer to the UART module operation structure.
|
||||
* @param[in] s null-terminated string to send.
|
||||
*/
|
||||
void hal_uart_puts(const hal_uart_descriptor_t * descriptor, const char * s);
|
||||
|
||||
/**
|
||||
* @brief Receives data in a non-blocking way.
|
||||
*
|
||||
* @param[in] descriptor pointer to the UART module operation structure.
|
||||
* @param[out] data pointer to the user-side buffer used to receive data.
|
||||
* @param[in] length number of bytes to receive.
|
||||
*
|
||||
* If descriptor has a non-null \a read_buffer_ptr, then this function is used to
|
||||
* copy input characters from it to \a data.
|
||||
* If \a read_buffer_ptr is NULL, then this function ignores all inputs.
|
||||
*/
|
||||
void hal_uart_read(const hal_uart_descriptor_t * descriptor,
|
||||
uint8_t * data,
|
||||
const size_t length);
|
||||
|
||||
/**
|
||||
* @brief Returns number of bytes available to read from the income buffer of the
|
||||
* driver.
|
||||
*
|
||||
* @param[in] descriptor pointer to driver structure.
|
||||
*
|
||||
* @return Number of bytes available to read.
|
||||
*/
|
||||
size_t hal_uart_read_buffer_size_get(const hal_uart_descriptor_t * descriptor);
|
||||
|
||||
/**
|
||||
* @brief Returns number of bytes available to write to the outgoing buffer of the
|
||||
* driver.
|
||||
*
|
||||
* @param[in] descriptor pointer to driver structure.
|
||||
*
|
||||
* @return Number of bytes available to write.
|
||||
*/
|
||||
size_t hal_uart_write_buffer_size_get(const hal_uart_descriptor_t * descriptor);
|
||||
|
||||
/**
|
||||
* @brief This function deallocates resources previously allocated by hal_uart_open.
|
||||
*
|
||||
* @param[in] descriptor pointer to driver structure.
|
||||
*
|
||||
* @return Return status of operation.
|
||||
*/
|
||||
hal_uart_error_t hal_uart_close(const hal_uart_descriptor_t * descriptor);
|
||||
|
||||
|
||||
#if defined(CONFIG_TRACE) && defined(CONFIG_DEBUG)
|
||||
|
||||
/**
|
||||
* @brief Finalizes remaining trace data output to UART.
|
||||
*
|
||||
* @details This debugging feature is needed to finalize buffered trace output
|
||||
* to UART before commencing non-buffered assertion output.
|
||||
*/
|
||||
void hal_uart_trace_finalize(void);
|
||||
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_UART_H_INCLUDED */
|
|
@ -0,0 +1,105 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_UART_TASK_SCHEDULER_H_INCLUDED
|
||||
#define HAL_UART_TASK_SCHEDULER_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "hal_atomic.h"
|
||||
#include "hal_task_scheduler.h"
|
||||
#include "sys_utils.h"
|
||||
|
||||
/**
|
||||
* @defgroup hal_uart_task_scheduler HAL UART Task Scheduler
|
||||
* @ingroup hal_15_4
|
||||
* @{
|
||||
* @brief Module to declare HAL UART Task Scheduler interface
|
||||
*/
|
||||
|
||||
/**@brief Identifiers for registered UART event handlers.
|
||||
*
|
||||
* @details enumeration with identifiers of registered UART event handlers.
|
||||
* UART handlers will be called from the HAL_UART task. */
|
||||
typedef enum
|
||||
{
|
||||
HAL_UART_RX_TASK_ID,
|
||||
HAL_UART_TX_TASK_ID,
|
||||
HAL_UART_ERROR_TASK_ID,
|
||||
HAL_UART_TASKS_AMOUNT,
|
||||
} hal_uart_task_id_t;
|
||||
|
||||
/**@brief Prototype of a UART task handler.
|
||||
*
|
||||
* @details Handler which will be called from HAL_UART task. */
|
||||
typedef void (* hal_uart_task_handler_t)(uint32_t channel);
|
||||
|
||||
void hal_uart_rx_handler(uint32_t channel);
|
||||
void hal_uart_tx_handler(uint32_t channel);
|
||||
void hal_uart_error_handler(uint32_t channel);
|
||||
|
||||
/**@brief UART channels.
|
||||
*
|
||||
* @details Array which includes event id for every channel it happened. */
|
||||
extern volatile uint16_t g_hal_uart_modules_tasks[CONFIG_HAL_UART_CHANNELS];
|
||||
|
||||
|
||||
/**@brief Notifies HAL task scheduler to add an UART task for execution.
|
||||
*
|
||||
* @details The function sets a marker for the UART event task for execution.
|
||||
* And sets this marker for a channel where event happened.
|
||||
*
|
||||
* @param[in] channel event channel.
|
||||
* @param[in] hal_uart_task_id HAL task identificator. */
|
||||
static inline void hal_uart_task_post(uint32_t channel,
|
||||
uint8_t hal_uart_task_id)
|
||||
{
|
||||
atomic_t atomic = 0;
|
||||
|
||||
hal_atomic_start(&atomic);
|
||||
g_hal_uart_modules_tasks[channel] |= BIT(hal_uart_task_id);
|
||||
hal_atomic_end(&atomic);
|
||||
|
||||
hal_task_post(HAL_UART_TASK_ID);
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_UART_TASK_SCHEDULER_H_INCLUDED */
|
|
@ -0,0 +1,90 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_EXCEPTIONS_H_INCLUDED
|
||||
#define HAL_EXCEPTIONS_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* @defgroup hal_15_4_nrf52 Chip-specific library interface
|
||||
* @ingroup hal_15_4
|
||||
*
|
||||
* @defgroup hal_nrf52_exceptions HAL exceptions
|
||||
* @ingroup hal_15_4_nrf52
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @brief Size of stack dump in 4-byte words.*/
|
||||
#define HAL_EXCEPTIONS_DUMP_SIZE 16
|
||||
/** @brief Defines where to put a '\n' in stack dump.
|
||||
*
|
||||
* This value defines power of 2 items in one row.
|
||||
* E.g. 3 gives 2 ^ 3 = 8 items in a row.*/
|
||||
#define HAL_EXCEPTIONS_ITEMS_IN_LINE 3
|
||||
|
||||
/** @brief This structure holds values of fault status registers.*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t CFSR; /*!< Configurable Fault Status Register.*/
|
||||
uint32_t HFSR; /*!< HardFault Status Register.*/
|
||||
uint32_t DFSR; /*!< Debug Fault Status Register.*/
|
||||
uint32_t AFSR; /*!< Auxiliary Fault Status Register.*/
|
||||
} hal_exceptions_status_registers_t;
|
||||
|
||||
/** @brief This structure is put into dump monitor port and holds values of said
|
||||
* registers when exception has happen.*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t R0; /**< Register R0 (Argument 1 / word result).*/
|
||||
uint32_t R1; /**< Register R1 (Argument 2 / double-word result).*/
|
||||
uint32_t R2; /**< Register R2 (Argument 3).*/
|
||||
uint32_t R3; /**< Register R3 (Argument 4).*/
|
||||
uint32_t R12; /**< Register R12 (Scratch register (corruptible)).*/
|
||||
uint32_t LR; /**< Link register (R14).*/
|
||||
uint32_t PC; /**< Program counter (R15).*/
|
||||
uint32_t PSR; /**< Combined processor status register.*/
|
||||
uint32_t* FP; /**< Value of register, which may be used as Frame Pointer.*/
|
||||
} hal_exceptions_dump_t;
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // HAL_EXCEPTIONS_H_INCLUDED
|
|
@ -0,0 +1,107 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_NRF52_RTC_H_INCLUDED
|
||||
#define HAL_NRF52_RTC_H_INCLUDED
|
||||
|
||||
#include "nordic_common.h"
|
||||
#include "nrf_drv_config.h"
|
||||
#include "nrf_drv_common.h"
|
||||
#include "nrf_drv_rtc.h"
|
||||
#include "nrf_rtc.h"
|
||||
|
||||
/**
|
||||
* @defgroup hal_nrf52_rtc HAL RTC
|
||||
* @ingroup hal_15_4_nrf52
|
||||
* @{
|
||||
*/
|
||||
|
||||
// RTC counter bitlenght
|
||||
#define LAGEST_PRESCALER_VALUE 4096
|
||||
// RTC counter bitlenght
|
||||
#define RTC_CNT_BITLENGHT 24
|
||||
// Longest sleep time, ms
|
||||
#define LONGEST_SLEEP_TIME ((( 1UL << RTC_CNT_BITLENGHT ) \
|
||||
/(RTC_INPUT_FREQ/LAGEST_PRESCALER_VALUE)) * 1000UL )
|
||||
|
||||
// Shortest sleep time, ms
|
||||
#define SHORTEST_SLEEP_TIME 1
|
||||
|
||||
/**@brief Function for initialize low frequency clock
|
||||
*/
|
||||
void rtc_lfclk_start(void);
|
||||
|
||||
|
||||
/** @brief Function initialization and configuration of RTC driver instance.
|
||||
*
|
||||
* @param[in] sleep_time_ms after this time compare event will be triggered
|
||||
*/
|
||||
void rtc_start(uint32_t sleep_time_ms);
|
||||
|
||||
/** @brief Stop RTC
|
||||
*/
|
||||
void rtc_stop(void);
|
||||
|
||||
/** @brief Get RTC counter
|
||||
*
|
||||
* @retval uint32_t Contents of RTC counter register.
|
||||
*/
|
||||
uint32_t rtc_cnt_get(void);
|
||||
|
||||
/** @brief Get time elapsed since cnt_ticks
|
||||
*
|
||||
* @param[in] cnt_ticks Number of rtc-ticks
|
||||
*
|
||||
* @retval uint32_t Time since cnt_ticks, ms
|
||||
*/
|
||||
uint64_t get_rtc_time_since(uint32_t cnt_ticks);
|
||||
|
||||
/** @brief Check if rtc compare interrupt was triggered after calling
|
||||
* rtc_start function
|
||||
*
|
||||
* @retval bool true - compare interrupt was triggered
|
||||
* false - it wasn't
|
||||
*/
|
||||
bool is_rtc_comp_irq_triggerd(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* HAL_NRF52_RTC_H_INCLUDED */
|
|
@ -0,0 +1,75 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 HAL_NRF52_TIMER_INCLUDED
|
||||
#define HAL_NRF52_TIMER_INCLUDED
|
||||
|
||||
/**
|
||||
* @defgroup hal_nrf52_timer HAL timer - additional features
|
||||
* @ingroup hal_15_4_nrf52
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**@brief Pause hardware timer.
|
||||
*/
|
||||
void hal_timer_pause(void);
|
||||
|
||||
|
||||
/**@brief Resume hardware timer.
|
||||
*/
|
||||
void hal_timer_resume(void);
|
||||
|
||||
|
||||
/**@brief Set a new system time
|
||||
*
|
||||
* @param[in] time_us time to set.
|
||||
*/
|
||||
void hal_time_adjust(uint64_t time_us);
|
||||
|
||||
|
||||
/**@brief Uninit hardwware timer
|
||||
*/
|
||||
void hal_timer_uninit(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
|
||||
#endif /* HAL_NRF52_TIMER_INCLUDED */
|
|
@ -0,0 +1,61 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_AUTO_REQUEST_H_INCLUDED
|
||||
#define MAC_AUTO_REQUEST_H_INCLUDED
|
||||
|
||||
/** @file
|
||||
*
|
||||
* @defgroup mac_auto_request MAC auto request
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief This function is called when a new beacon has been sent.
|
||||
*
|
||||
* @param[in] p_ind - Pointer to beacon indication structure.
|
||||
*/
|
||||
void mac_auto_request_notify_ind(mac_beacon_ind_t * p_ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* MAC_AUTO_REQUEST_H_INCLUDED_ */
|
|
@ -0,0 +1,467 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_COMMON_H_INCLUDED
|
||||
#define MAC_COMMON_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "phy_common.h"
|
||||
|
||||
#if (CONFIG_SECURE == 1)
|
||||
#include "mac_security.h"
|
||||
#endif
|
||||
|
||||
/** @file
|
||||
* Types and declarations common for different MLME transactions listed here.
|
||||
*
|
||||
* @defgroup mac_common MAC Common API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module for declaring MAC Common API.
|
||||
* @details The Common MAC module contains declarations of commonly used MAC routines and necessary
|
||||
* macros and types.
|
||||
*/
|
||||
|
||||
/**@brief Maximum interval for acknowledgement frame to arrive in microseconds.
|
||||
*
|
||||
* macAckWaitDuration = aUnitBackoffPeriod(only for beacon enabled PAN) +
|
||||
* aTurnaroundTime +
|
||||
* phySHRDuration + ceil(6 * phySymbolsPerOctet) =
|
||||
* 20 + 12 + 10 + 6 * 2 =
|
||||
* 54 symbols / 62.5 ksymbols/s = 864 us (544 us for beacon disabled PAN)
|
||||
*/
|
||||
#if (CONFIG_BEACON_ENABLED == 1)
|
||||
#define macAckWaitDuration 864
|
||||
#else
|
||||
#define macAckWaitDuration 544
|
||||
#endif
|
||||
|
||||
/**@brief The maximum number of octets added by the MAC
|
||||
* sublayer to the MAC payload of a beacon frame.
|
||||
*/
|
||||
#define aMaxBeaconOverhead 75
|
||||
|
||||
/**@brief The number of symbols forming the basic time period
|
||||
* used by the CSMA-CA algorithm.
|
||||
*/
|
||||
#define aUnitBackoffPeriod 20UL
|
||||
|
||||
/**@brief The number of symbols forming a superframe slot
|
||||
* when the superframe order is equal to 0.
|
||||
*/
|
||||
#define aBaseSlotDuration 60UL
|
||||
|
||||
/**@brief The number of slots contained in any superframe. */
|
||||
#define aNumSuperframeSlots 16UL
|
||||
|
||||
/**@brief The number of symbols forming a superframe when
|
||||
* the superframe order is equal to 0.
|
||||
*/
|
||||
#define aBaseSuperframeDuration (aBaseSlotDuration * aNumSuperframeSlots)
|
||||
|
||||
/**@brief The maximum size, in octets, of a beacon payload. */
|
||||
#define aMaxBeaconPayloadLength (aMaxPHYPacketSize - aMaxBeaconOverhead)
|
||||
|
||||
/**@brief The maximum number of octets added by the MAC
|
||||
* sublayer to the PSDU without security.
|
||||
*/
|
||||
#define aMaxMPDUUnsecuredOverhead 25
|
||||
|
||||
/**@brief The maximum number of octets that can be transmitted in the MAC Payload
|
||||
* field of an unsecured MAC frame that will be guaranteed not to exceed aMaxPHYPacketSize.
|
||||
*/
|
||||
#define aMaxMACSafePayloadSize (aMaxPHYPacketSize - aMaxMPDUUnsecuredOverhead)
|
||||
|
||||
/**@brief The minimum number of octets added by the MAC sublayer to the PSDU.*/
|
||||
#define aMinMPDUOverhead 9
|
||||
|
||||
/**@brief The maximum number of octets that can be transmitted in the MAC
|
||||
* Payload field.
|
||||
*/
|
||||
#define aMaxMACPayloadSize (aMaxPHYPacketSize - aMinMPDUOverhead)
|
||||
|
||||
/**@brief The maximum size of an MPDU, in octets, that can be followed by a SIFS period. */
|
||||
#define aMaxSIFSFrameSize 18
|
||||
|
||||
/**@brief The minimum number of symbols forming the CAP.
|
||||
*
|
||||
* @details This ensures that MAC commands can still be transferred to devices
|
||||
* when GTSs are being used.
|
||||
*/
|
||||
#define aMinCAPLength 440
|
||||
|
||||
/**@brief The number of superframes in which a GTS descriptor exists
|
||||
* in the beacon frame of the PAN coordinator.
|
||||
*/
|
||||
#define aGTSDescPersistenceTime 4
|
||||
|
||||
/**@brief The number of consecutive lost beacons that will cause the MAC sublayer
|
||||
* of a receiving device to declare a loss of synchronization.
|
||||
*/
|
||||
#define aMaxLostBeacons 4
|
||||
|
||||
/**@brief Maximum number of battery life extension periods. */
|
||||
#define MAC_MIN_BATT_LIFE_EXT_PERIODS 6
|
||||
/**@brief Minimum number of battery life extension periods. */
|
||||
#define MAC_MAX_BATT_LIFE_EXT_PERIODS 41
|
||||
|
||||
/**@brief Minimum value for macBeaconOrder parameter. */
|
||||
#define MAC_MIN_BEACON_ORDER 0
|
||||
/**@brief Maximum value for macBeaconOrder parameter. */
|
||||
#define MAC_MAX_BEACON_ORDER 15
|
||||
|
||||
/**@brief Minimum value for macMaxCSMABackoffs parameter. */
|
||||
#define MAC_MIN_MAX_CSMA_BACKOFFS 0
|
||||
/**@brief Maximum value for macMaxCSMABackoffs parameter. */
|
||||
#define MAC_MAX_MAX_CSMA_BACKOFFS 5
|
||||
|
||||
/**@brief Minimum value for macMinBE parameter. */
|
||||
#define MAC_MIN_MIN_BE 0
|
||||
|
||||
/**@brief Minimum value for macMaxBE parameter. */
|
||||
#define MAC_MIN_MAX_BE 3
|
||||
/**@brief Maximum value for macMaxBE parameter. */
|
||||
#define MAC_MAX_MAX_BE 8
|
||||
|
||||
/**@brief Minimum value for macSuperframeOrder parameter. */
|
||||
#define MAC_MIN_SUPERFRAME_ORDER 0
|
||||
/**@brief Maximum value for macSuperframeOrder parameter. */
|
||||
#define MAC_MAX_SUPERFRAME_ORDER 15
|
||||
|
||||
/**@brief Minimum value for macMaxFrameRetries parameter. */
|
||||
#define MAC_MIN_MAX_FRAME_RETRIES 0
|
||||
/**@brief Maximum value for macMaxFrameRetries parameter. */
|
||||
#define MAC_MAX_MAX_FRAME_RETRIES 7
|
||||
|
||||
/**@brief Minimum value for macResponseWaitTime parameter. */
|
||||
#define MAC_MIN_RESPONSE_WAIT_TIME 2
|
||||
/**@brief Maximum value for macResponseWaitTime parameter. */
|
||||
#define MAC_MAX_RESPONSE_WAIT_TIME 64
|
||||
|
||||
/**@brief A handy macro for a never initialized short address. */
|
||||
#define MAC_SHORT_ADDRESS_NOT_SET 0xFFFF
|
||||
|
||||
/**@brief A handy macro for a never initialized short address. */
|
||||
#define MAC_EXTENDED_ADDRESS_NOT_SET 0xFFFFFFFFFFFFFFFFULL
|
||||
|
||||
/**@brief A value of MAC beacon order attribute which determines
|
||||
* a state with no periodic beacons.
|
||||
*/
|
||||
#define MAC_NO_BEACONS 15
|
||||
|
||||
/**@brief A handy macro for broadcast address. */
|
||||
#define MAC_BROADCAST_SHORT_ADDRESS 0xFFFF
|
||||
|
||||
/**@brief A handy macro for unknown PAN ID. */
|
||||
#define MAC_BROADCAST_PANID 0xFFFF
|
||||
|
||||
/**@brief Short address field value that is used when the device does not
|
||||
* support short addressing mode.
|
||||
*/
|
||||
#define MAC_EXTENDED_ADDRESS_ONLY 0xFFFE
|
||||
|
||||
/**@brief Final CAP slot field value in the beacon for non-beacon enabled PAN. */
|
||||
#define MAC_FINAL_CAP_SLOT_NBPAN 15
|
||||
|
||||
/**@brief Total amount of slots available in beacon enabled PAN. */
|
||||
#define MAC_SLOT_AMOUNT 16
|
||||
|
||||
/**@brief This is the value of auto request key index until it has been set. */
|
||||
#define MAC_SECURITY_KEY_INDEX_NOT_SET 0xFF
|
||||
|
||||
/**@brief Length of short MAC address in bytes. */
|
||||
#define MAC_ADDR_SHORT_LEN 2
|
||||
|
||||
/**@brief Length of extended MAC address in bytes. */
|
||||
#define MAC_ADDR_EXTENDED_LEN 8
|
||||
|
||||
/**@brief Length of PAN ID field in bytes. */
|
||||
#define MAC_PAN_ID_LEN 2
|
||||
|
||||
/**@brief MAC footer (FCS) size. */
|
||||
#define MAC_MFR_SIZE 2
|
||||
|
||||
/**@brief Maximum auxiliary header length */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
#define MAC_MAX_AUX_HEADER_SIZE 14
|
||||
#else
|
||||
#define MAC_MAX_AUX_HEADER_SIZE 0
|
||||
#endif
|
||||
|
||||
/**@brief Maximum MAC header length */
|
||||
#define MAC_MAX_MHR_SIZE (PHY_MAX_HEADER_SIZE + \
|
||||
2 /* Frame control */ + \
|
||||
1 /* Data sequence number */ + \
|
||||
2 * (sizeof(uint16_t) + (sizeof(uint64_t))) /* Two PAN IDs and extended addresses */ + \
|
||||
MAC_MAX_AUX_HEADER_SIZE)
|
||||
/**@brief Maximum MAC header length for beacon frame */
|
||||
#define MAC_MAX_BCN_MHR_SIZE (PHY_MAX_HEADER_SIZE + \
|
||||
2 /* Frame control field */ + \
|
||||
1 /* Beacon sequence number */ + \
|
||||
sizeof(uint16_t) /* PAN ID */ + \
|
||||
sizeof(uint64_t) /* Extended address */ + \
|
||||
MAC_MAX_AUX_HEADER_SIZE)
|
||||
|
||||
|
||||
/**@brief Memory which should be reserved for MAC fields */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
#define MAC_MEMORY_RESERVE (MAC_MAX_MHR_SIZE + MAX_MIC_SIZE + MAC_MFR_SIZE)
|
||||
#else
|
||||
#define MAC_MEMORY_RESERVE (MAC_MAX_MHR_SIZE + MAC_MFR_SIZE)
|
||||
#endif
|
||||
|
||||
/**@brief Offset of MAC payload in the frame buffer */
|
||||
#define MAC_MAX_MSDU_OFFSET MAC_MAX_MHR_SIZE
|
||||
|
||||
/**@brief Possible MAC frame types. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_BEACON, /**< Frame is a beacon. */
|
||||
MAC_DATA, /**< Frame is a data frame. */
|
||||
MAC_ACK, /**< Frame is a MAC ACKnowledgement. */
|
||||
MAC_COMMAND /**< Frame is a MAC command. */
|
||||
} mac_frame_type_t;
|
||||
|
||||
/**@brief MAC ADDRESS. */
|
||||
typedef union
|
||||
{
|
||||
uint16_t short_address; /**< 16-bit short address. */
|
||||
uint64_t long_address; /**< 64-bit long address. */
|
||||
} mac_addr_t;
|
||||
|
||||
/**@brief MAC ADDR MODE. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_ADDR_NONE = 0, /**< NO address is used. */
|
||||
MAC_ADDR_SHORT = 2, /**< Short address is used. */
|
||||
MAC_ADDR_LONG = 3 /**< Long address is used. */
|
||||
} mac_addr_mode_t;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
MAC_FRAME_VERSION_2003, /**< IEEE 802.15.4-2003 compliant. */
|
||||
MAC_FRAME_VERSION_2006 /**< IEEE 802.15.4-2006 compliant. */
|
||||
} mac_frame_version_t;
|
||||
|
||||
/**
|
||||
* @brief MAC status
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.17
|
||||
* excluding:
|
||||
* MAC_IS_NOT_AVAILABLE
|
||||
* This status is necessary for synchronous API.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MAC_SUCCESS = 0x00, /* 0 */ /**< Operation is successful. */
|
||||
MAC_COUNTER_ERROR = 0xDB, /* 219 */ /**< The frame counter purportedly applied
|
||||
by the originator of the received
|
||||
frame is invalid. */
|
||||
MAC_IMPROPER_KEY_TYPE = 0xDC, /* 220 */ /**< The key purportedly applied by the
|
||||
originator of the received frame is
|
||||
not allowed to be used with that
|
||||
frame type according to the key usage
|
||||
policy of the recipient. */
|
||||
MAC_IMPROPER_SECURITY_LEVEL = 0xDD, /* 221 */ /**< The security level purportedly applied
|
||||
by the originator of the received
|
||||
frame does not meet the minimum
|
||||
security level required/expected by
|
||||
the recipient for that frame type. */
|
||||
MAC_UNSUPPORTED_LEGACY = 0xDE, /* 222 */ /**< The received frame was purportedly
|
||||
secured using security based on IEEE
|
||||
Std 802.15.4-2003, and such security
|
||||
is not supported by this standard. */
|
||||
MAC_UNSUPPORTED_SECURITY = 0xDF, /* 223 */ /**< The security purportedly applied by
|
||||
the originator of the received frame
|
||||
is not supported. */
|
||||
MAC_BEACON_LOSS = 0xE0, /* 224 */ /**< The beacon was lost following a
|
||||
synchronization request. */
|
||||
MAC_CHANNEL_ACCESS_FAILURE = 0xE1, /* 225 */ /**< A transmission could not take place
|
||||
due to activity on the channel, i.e.
|
||||
the CSMA-CA mechanism has failed. */
|
||||
MAC_DENIED = 0xE2, /* 226 */ /**< The GTS request has been denied by
|
||||
the PAN coordinator. */
|
||||
MAC_DISABLE_TRX_FAILURE = 0xE3, /* 227 */ /**< The attempt to disable the
|
||||
transceiver has failed. */
|
||||
MAC_SECURITY_ERROR = 0xE4, /* 228 */ /**< Cryptographic processing of the
|
||||
received secured frame failed. */
|
||||
MAC_FRAME_TOO_LONG = 0xE5, /* 229 */ /**< Either a frame resulting from
|
||||
processing has a length that is
|
||||
greater than aMaxPHYPacketSize or
|
||||
a requested transaction is too large
|
||||
to fit in the CAP or GTS. */
|
||||
MAC_INVALID_GTS = 0xE6, /* 230 */ /**< The requested GTS transmission failed
|
||||
because the specified GTS either did
|
||||
not have a transmit GTS direction or
|
||||
was not defined. */
|
||||
MAC_INVALID_HANDLE = 0xE7, /* 231 */ /**< A request to purge an MSDU from the
|
||||
transaction queue was made using an
|
||||
MSDU handle that was not found in
|
||||
the transaction table. */
|
||||
MAC_INVALID_PARAMETER = 0xE8, /* 232 */ /**< A parameter in the primitive is
|
||||
either not supported or is out of
|
||||
the valid range. */
|
||||
MAC_NO_ACK = 0xE9, /* 233 */ /**< No acknowledgment was received after
|
||||
macMaxFrameRetries. */
|
||||
MAC_NO_BEACON = 0xEA, /* 234 */ /**< A scan operation failed to find any
|
||||
network beacons. */
|
||||
MAC_NO_DATA = 0xEB, /* 235 */ /**< No response data was available
|
||||
following a request. */
|
||||
MAC_NO_SHORT_ADDRESS = 0xEC, /* 236 */ /**< The operation failed because a 16-bit
|
||||
short address was not allocated. */
|
||||
MAC_OUT_OF_CAP = 0xED, /* 237 */ /**< A receiver enable request was
|
||||
unsuccessful because it could not be
|
||||
completed within the CAP.
|
||||
@note The enumeration description is
|
||||
not used in this standard, and it is
|
||||
included only to meet the backwards
|
||||
compatibility requirements for
|
||||
IEEE Std 802.15.4-2003. */
|
||||
MAC_PAN_ID_CONFLICT = 0xEE, /* 238 */ /**< A PAN identifier conflict has been
|
||||
detected and communicated to the PAN
|
||||
coordinator. */
|
||||
MAC_REALIGNMENT = 0xEF, /* 239 */ /**< A coordinator realignment command has
|
||||
been received. */
|
||||
MAC_TRANSACTION_EXPIRED = 0xF0, /* 240 */ /**< The transaction has expired and its
|
||||
information was discarded. */
|
||||
MAC_TRANSACTION_OVERFLOW = 0xF1, /* 241 */ /**< There is no capacity to store the
|
||||
transaction. */
|
||||
MAC_TX_ACTIVE = 0xF2, /* 242 */ /**< The transceiver was in the transmitter
|
||||
enabled state when the receiver was
|
||||
requested to be enabled.
|
||||
@note The enumeration description is
|
||||
not used in this standard, and it is
|
||||
included only to meet the backwards
|
||||
compatibility requirements for
|
||||
IEEE Std 802.15.4-2003. */
|
||||
MAC_UNAVAILABLE_KEY = 0xF3, /* 243 */ /**< The key purportedly used by the
|
||||
originator of the received frame is
|
||||
not available or, if available, the
|
||||
originating device is not known or is
|
||||
blacklisted with that particular
|
||||
key. */
|
||||
MAC_UNSUPPORTED_ATTRIBUTE = 0xF4, /* 244 */ /**< A SET/GET request was issued with the
|
||||
identifier of a PIB attribute that is
|
||||
not supported. */
|
||||
MAC_INVALID_ADDRESS = 0xF5, /* 245 */ /**< A request to send data was
|
||||
unsuccessful because neither the source
|
||||
address parameters nor the destination
|
||||
address parameters were present. */
|
||||
MAC_ON_TIME_TOO_LONG = 0xF6, /* 246 */ /**< A receiver enable request was
|
||||
unsuccessful because it specified a
|
||||
number of symbols that was longer than
|
||||
the beacon interval. */
|
||||
MAC_PAST_TIME = 0xF7, /* 247 */ /**< A receiver enable request was
|
||||
unsuccessful because it could not be
|
||||
completed within the current superframe
|
||||
and was not permitted to be deferred
|
||||
until the next superframe. */
|
||||
MAC_TRACKING_OFF = 0xF8, /* 248 */ /**< The device was instructed to start
|
||||
sending beacons based on the timing
|
||||
of the beacon transmissions of its
|
||||
coordinator, but the device is not
|
||||
currently tracking the beacon of its
|
||||
coordinator. */
|
||||
MAC_INVALID_INDEX = 0xF9, /* 249 */ /**< An attempt to write to a MAC PIB
|
||||
attribute that is in a table failed
|
||||
because the specified table index
|
||||
was out of range. */
|
||||
MAC_LIMIT_REACHED = 0xFA, /* 250 */ /**< A scan operation terminated
|
||||
prematurely because the number of
|
||||
PAN descriptors stored reached an
|
||||
implementation specified maximum. */
|
||||
MAC_READ_ONLY = 0xFB, /* 251 */ /**< A SET/GET request was issued with the
|
||||
identifier of an attribute that is
|
||||
read only. */
|
||||
MAC_SCAN_IN_PROGRESS = 0xFC, /* 252 */ /**< A request to perform a scan operation
|
||||
failed because the MLME was in the
|
||||
process of performing a previously
|
||||
initiated scan operation. */
|
||||
MAC_SUPERFRAME_OVERLAP = 0xFD, /* 253 */ /**< The device was instructed to start
|
||||
sending beacons based on the timing
|
||||
of the beacon transmissions of its
|
||||
coordinator, but the instructed start
|
||||
time overlapped the transmission time
|
||||
of the beacon of its coordinator. */
|
||||
/* Statuses out from standard. It is used for synchronous API */
|
||||
MAC_IS_NOT_AVAILABLE = 0xFF /* 255 */ /**< MAC is not available. */
|
||||
} mac_status_t;
|
||||
|
||||
/**
|
||||
* @brief Payload descriptor.
|
||||
*
|
||||
* @details Not covered by the standard.
|
||||
* Contains information sufficient to allow the next higher layer to clean
|
||||
* the memory allocated for incoming frames.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/**
|
||||
* Pointer to the set of octets forming the frame payload being indicated by
|
||||
* the MAC sublayer entity.
|
||||
*/
|
||||
uint8_t * p_payload;
|
||||
/**
|
||||
* Offset of the payload data relative to the beginning of the frame.
|
||||
* Equal to the MAC header.
|
||||
*/
|
||||
uint8_t payload_offset;
|
||||
} mac_payload_descriptor_t;
|
||||
|
||||
/** @brief Command frame IDs defined by the MAC sublayer that are listed
|
||||
* in Table 82 of the standard.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MAC_CMD_ASSOC_REQ = 0x01, /**< Association request.*/
|
||||
MAC_CMD_ASSOC_RESP = 0x02, /**< Association response.*/
|
||||
MAC_CMD_DISASSOC_NTF = 0x03, /**< Disassociation notification.*/
|
||||
MAC_CMD_DATA_REQ = 0x04, /**< Data request.*/
|
||||
MAC_CMD_PANID_CONFLICT_NTF = 0x05, /**< PAN ID conflict notification.*/
|
||||
MAC_CMD_ORPHAN_NTF = 0x06, /**< Orphan notification.*/
|
||||
MAC_CMD_BEACON_REQ = 0x07, /**< Beacon request.*/
|
||||
MAC_CMD_COORD_REALIGN = 0x08, /**< Coordinator realignment.*/
|
||||
MAC_CMD_GTS_REQ = 0x09 /**< GTS request.*/
|
||||
} mac_command_id_t;
|
||||
/** @} */
|
||||
|
||||
|
||||
#endif // MAC_COMMON_H_INCLUDED
|
|
@ -0,0 +1,333 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MCPS_DATA_H_INCLUDED
|
||||
#define MAC_MCPS_DATA_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC Data module declares the MAC Data transmittion routines and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_data MAC MCPS Data API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MCPS Data API.
|
||||
* @details The MAC MCPS Data module declares the MAC Data transmission routines and necessary types according
|
||||
* to the MAC specification. More specifically, MAC data request mcps_data_req(), and MAC Data
|
||||
* indication mcps_data_ind() primitives are declared. The confirmation callback typedef is
|
||||
* declared as mcps_data_conf_cb_t.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief TX options bit fields.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.1.
|
||||
*/
|
||||
#define TX_ACKNOWLEDGED_BIT (0)
|
||||
#define TX_GTS_BIT (1)
|
||||
#define TX_INDIRECT_BIT (2)
|
||||
|
||||
|
||||
/**
|
||||
* @brief TX options for MAC data transmission.
|
||||
*
|
||||
* @details The three bits (b0, b1, b2) indicate the transmission options for this MSDU.
|
||||
* For b0, 1 = acknowledged transmission, 0 = unacknowledged transmission.
|
||||
* For b1, 1 = GTS transmission, 0 = CAP transmission for a beacon-enabled PAN.
|
||||
* For b2, 1 = indirect transmission, 0 = direct transmission.
|
||||
* For a nonbeacon-enabled PAN, bit b1 should always be set to 0.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t ack : 1;
|
||||
uint8_t gts : 1;
|
||||
uint8_t indirect : 1;
|
||||
uint8_t : 5;
|
||||
} mac_tx_options_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPS-DATA.confirm.
|
||||
*
|
||||
* @details The MCPS-DATA.confirm primitive reports the results of a request to transfer
|
||||
* a data SPDU (MSDU) from a local SSCS entity to a single peer SSCS entity.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.2.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** The handle associated with the MSDU being confirmed. */
|
||||
uint8_t msdu_handle;
|
||||
|
||||
/** The status of the last MSDU transmission. */
|
||||
mac_status_t status;
|
||||
|
||||
/**
|
||||
* Optional. The time, in symbols, at which the data was transmitted (see 7.5.4.1).
|
||||
*
|
||||
* The value of this parameter will be considered valid only if the value of the
|
||||
* status parameter is SUCCESS; if the status parameter is not equal to
|
||||
* SUCCESS, the value of the Timestamp parameter will not be used for any other
|
||||
* purpose. The symbol boundary is described by macSyncSymbolOffset (see Table 86 in 7.4.1).
|
||||
*
|
||||
* This is a 24-bit value, and the precision of this value will be a minimum of 20 bits,
|
||||
* with the lowest 4 bits being the least significant.
|
||||
*/
|
||||
uint32_t timestamp;
|
||||
} mcps_data_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPS-DATA.request.
|
||||
*
|
||||
* @details The MCPS-DATA.request primitive requests the transfer of
|
||||
* a data SPDU (i.e., MSDU) from a local SSCS entity to a single peer SSCS entity.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.1.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mcps_data_conf_t confirm;
|
||||
|
||||
/**
|
||||
* The source addressing mode for this primitive and
|
||||
* subsequent MPDU. This value can take one of the following values:
|
||||
* @ref mac_addr_mode_t
|
||||
* 0x00 = no address (addressing fields omitted, see 7.2.1.1.8).
|
||||
* 0x01 = reserved.
|
||||
* 0x02 = 16-bit short address.
|
||||
* 0x03 = 64-bit extended address.
|
||||
*/
|
||||
mac_addr_mode_t src_addr_mode;
|
||||
|
||||
/**
|
||||
* The destination addressing mode for this primitive
|
||||
* and subsequent MPDU.
|
||||
* According to 7.1.1.1.1, Table 41.
|
||||
*/
|
||||
mac_addr_mode_t dst_addr_mode;
|
||||
|
||||
/** The 16-bit PAN identifier of the entity to which the MSDU is being transferred. */
|
||||
uint16_t dst_pan_id;
|
||||
|
||||
/** The individual device address of the entity to which the MSDU is being transferred. */
|
||||
mac_addr_t dst_addr;
|
||||
|
||||
/** The number of octets contained in the MSDU to be transmitted by
|
||||
* the MAC sublayer entity.
|
||||
*/
|
||||
uint8_t msdu_length;
|
||||
|
||||
/**
|
||||
* The pointer to the set of octets forming the MSDU
|
||||
* to be transmitted by the MAC sublayer entity.
|
||||
*
|
||||
* Caller must provide enough space for MAC and PHY header before this pointer.
|
||||
*/
|
||||
uint8_t * msdu;
|
||||
|
||||
/** The handle associated with the MSDU to be transmitted by the MAC sublayer entity. */
|
||||
uint8_t msdu_handle;
|
||||
|
||||
/**
|
||||
* The bits (b0, b1, b2) indicate the transmission options for this MSDU.
|
||||
* For b0, 1 = acknowledged transmission, 0 = unacknowledged transmission.
|
||||
* For b1, 1 = GTS transmission, 0 = CAP transmission for a beacon-enabled PAN.
|
||||
* For b2, 1 = indirect transmission, 0 = direct transmission.
|
||||
* For a nonbeacon-enabled PAN, bit b1 should always be set to 0.
|
||||
*/
|
||||
mac_tx_options_t tx_options;
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID node. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mcps_data_req_t;
|
||||
|
||||
/**
|
||||
* @brief Private information passed with MCPS-DATA.indication.
|
||||
* Not covered by the standard.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** RSSI value, which corresponds to packet that caused this indication. */
|
||||
int8_t rssi;
|
||||
/** Value of a pending bit from MHR. */
|
||||
uint8_t pending_bit;
|
||||
} mcps_data_ind_private_t;
|
||||
|
||||
/**
|
||||
* @brief MCPS-DATA.indication
|
||||
*
|
||||
* @details The MCPS-DATA.indication primitive indicates the transfer of
|
||||
* a data SPDU (i.e., MSDU) from the MAC sublayer to the local SSCS entity.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.3
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mcps_data_ind_private_t service;
|
||||
|
||||
/**
|
||||
* The source addressing mode for this primitive corresponding to the received MPDU.
|
||||
* According to 7.1.1.1.1, Table 43.
|
||||
*/
|
||||
mac_addr_mode_t src_addr_mode;
|
||||
|
||||
/** The 16-bit PAN identifier of the entity from which the MSDU was received. */
|
||||
uint16_t src_pan_id;
|
||||
|
||||
/** The individual device address of the entity from which the MSDU was received. */
|
||||
mac_addr_t src_addr;
|
||||
|
||||
/**
|
||||
* The destination addressing mode for this primitive corresponding to the received MPDU.
|
||||
* According to 7.1.1.1.1, Table 43.
|
||||
*/
|
||||
mac_addr_mode_t dst_addr_mode;
|
||||
|
||||
/** The 16-bit PAN identifier of the entity to which the MSDU is being transferred. */
|
||||
uint16_t dst_pan_id;
|
||||
|
||||
/** The individual device address of the entity to which the MSDU is being transferred. */
|
||||
mac_addr_t dst_addr;
|
||||
|
||||
/** The number of octets contained in the MSDU being indicated by the MAC sublayer entity. */
|
||||
uint8_t msdu_length;
|
||||
|
||||
/**
|
||||
* The information that is required for the next higher layer to read incoming message and to
|
||||
* free the memory allocated for this message.
|
||||
*/
|
||||
mac_payload_descriptor_t msdu;
|
||||
|
||||
/**
|
||||
* LQI value measured during reception of the MPDU.
|
||||
* Lower values represent lower LQI (see 6.9.8).
|
||||
*/
|
||||
uint8_t mpdu_link_quality;
|
||||
|
||||
/** The DSN of the received data frame. */
|
||||
uint8_t dsn;
|
||||
|
||||
/**
|
||||
* Optional. The time, in symbols, at which the data was received (see 7.5.4.1).
|
||||
* The symbol boundary is described by macSyncSymbolOffset (see Table 86 in 7.4.1).
|
||||
*
|
||||
* This is a 24-bit value, and the precision of this value shall be a minimum of 20 bits,
|
||||
* with the lowest 4 bits being the least significant.
|
||||
*/
|
||||
uint32_t timestamp;
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID node. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mcps_data_ind_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Confirmation function.
|
||||
*
|
||||
* @details The MCPS-DATA.confirm primitive is generated by the MAC sublayer
|
||||
* entity in response to an MCPS-DATA. request primitive. The MCPS-DATA.confirm
|
||||
* primitive returns a status of either SUCCESS, indicating that the request to
|
||||
* transmit was successful, or the appropriate error code.
|
||||
* The status values are fully described in 7.1.1.1.3 and subclauses referenced by 7.1.1.1.3.
|
||||
*
|
||||
* @param Pointer to confirmation primitive.
|
||||
*/
|
||||
typedef void (* mcps_data_conf_cb_t)(mcps_data_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPS-DATA.request service
|
||||
*
|
||||
* @details The MCPS-DATA.request primitive is generated by a local SSCS entity
|
||||
* when a data SPDU (i.e., MSDU) is to be transferred to a peer SSCS entity.
|
||||
* After request completion, user callback will be issued with
|
||||
* valid data stored in structure @ref mcps_data_conf_t.
|
||||
*
|
||||
* @param req Pointer to MCPS-DATA request structure.
|
||||
* @param conf_cb Pointer to confirmation function (user callback).
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.2.
|
||||
*/
|
||||
void mcps_data_req(mcps_data_req_t * req, mcps_data_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPS-DATA.indication handler.
|
||||
*
|
||||
* @details The MCPS-DATA.indication primitive is generated by the MAC sublayer and
|
||||
* issued to the SSCS on receipt of a data frame at the local MAC sublayer entity
|
||||
* that passes the appropriate message filtering operations as described in 7.5.6.2.
|
||||
*
|
||||
* @param ind MCPS-DATA.indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.3.
|
||||
*/
|
||||
extern void mcps_data_ind(mcps_data_ind_t * ind);
|
||||
|
||||
/**
|
||||
* @brief Free memory allocated for incoming message.
|
||||
*
|
||||
* @details The function will be invoked after all manipulations
|
||||
* with MSDU are completed. That is necessary to return the memory allocated by MAC
|
||||
* into the heap.
|
||||
*
|
||||
* @param p_payload_descriptor - Pointer to MSDU descriptor.
|
||||
*/
|
||||
void mac_mem_msdu_free(mac_payload_descriptor_t * p_payload_descriptor);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MCPS_DATA_H_INCLUDED
|
|
@ -0,0 +1,152 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MCPS_PURGE_H_INCLUDED
|
||||
#define MAC_MCPS_PURGE_H_INCLUDED
|
||||
|
||||
#if (CONFIG_PURGE_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC Purge module declares the MAC Purge routines and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_purge MAC MCPS Purge API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MCPS Purge API.
|
||||
* @details The MAC MCPS Purge module declares the MAC Purge routines and necessary types according to
|
||||
* the MAC specification. More specifically, MAC purge request mcps_purge_req(), and the
|
||||
* confirmation callback typedef is declared as mcps_purge_conf_cb_t. An additional primitive
|
||||
* not covered by the standard is declared. This is mpcs_purge() which is a synchronous version
|
||||
* of mcps_purge_req().
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MCPS-PURGE.confirm.
|
||||
*
|
||||
* @details The MCPS-PURGE.confirm primitive allows the MAC sublayer to notify the next higher layer
|
||||
* of the success of its request to purge an MSDU from the transaction queue.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.5.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** The handle of the MSDU to be purged from the transaction queue. */
|
||||
uint8_t msdu_handle;
|
||||
|
||||
/** The status of the request to be purged an MSDU from the transaction queue. */
|
||||
mac_status_t status;
|
||||
} mcps_purge_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPS-PURGE.request.
|
||||
*
|
||||
* @details The MCPS-PURGE.request primitive allows the next higher layer
|
||||
* to purge an MSDU from the transaction queue.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.4.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirmation to this request. */
|
||||
mcps_purge_conf_t confirm;
|
||||
|
||||
/** The handle of the MSDU to be purged from the transaction queue. */
|
||||
uint8_t msdu_handle;
|
||||
} mcps_purge_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Confirmation function.
|
||||
*
|
||||
* @details The MCPS-PURGE.confirm primitive is generated by the MAC sublayer
|
||||
* entity in response to an MCPS-PURGE.request primitive. The MCPS-PURGE.confirm
|
||||
* primitive returns a status of either SUCCESS, indicating that the purge request
|
||||
* was successful, or INVALID_HANDLE, indicating an error.
|
||||
* The status values are fully described in 7.1.1.4.3.
|
||||
*
|
||||
* @param Pointer to confirmation primitive.
|
||||
*/
|
||||
typedef void (* mcps_purge_conf_cb_t)(mcps_purge_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MCPS-PURGE.request service.
|
||||
*
|
||||
* @details The MCPS-PURGE.request primitive is generated by the next higher layer
|
||||
* whenever an MSDU is to be purged from the transaction queue.
|
||||
* After request completion, user callback will be issued with
|
||||
* valid data stored in structure mcps_purge_conf_t.
|
||||
*
|
||||
* @param req Pointer to MCPS-PURGE request structure.
|
||||
* @param conf_cb Pointer to the confirmation function (user callback).
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.1.4.
|
||||
*/
|
||||
void mcps_purge_req(mcps_purge_req_t * req, mcps_purge_conf_cb_t conf_cb);
|
||||
|
||||
/**
|
||||
* @brief Performs MCPS-PURGE.request directly (without request - confirm approach).
|
||||
*
|
||||
* @details Optional. Not covered by the standard.
|
||||
*
|
||||
* The MCPS-PURGE.request primitive is generated by the next higher layer
|
||||
* whenever an MSDU is to be purged from the transaction queue.
|
||||
*
|
||||
* @param req Pointer to MCPS-PURGE request structure.
|
||||
*
|
||||
* @return Result of the purge procedure.
|
||||
*/
|
||||
mac_status_t mcps_purge(mcps_purge_req_t * req);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_PURGE_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MCPS_PURGE_H_INCLUDED
|
|
@ -0,0 +1,336 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_ASSOCIATE_H_INCLUDED
|
||||
#define MAC_MLME_ASSOCIATE_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC Association module declares the MAC Association routines and necessary types/macros
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_assoc MAC MLME Association API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Association API.
|
||||
* @details The MLME Association module declares Association MAC routines and necessary macros/types according
|
||||
* to the MAC specification. More specifically, MLME Association request aka mlme_associate_req(),
|
||||
* MLME Association confirm callback typedef aka mlme_associate_conf_cb_t, MLME Association indication
|
||||
* as mlme_associate_ind(), and MLME Response aka mlme_associate_resp() primitives are declared.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Capability information field.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.3.1.2.
|
||||
*/
|
||||
#define ALTERNATE_PAN_COORDINATOR_BIT (0)
|
||||
#define DEVICE_TYPE_BIT (1)
|
||||
#define POWER_SOURCE_BIT (2)
|
||||
#define RECEIVER_ON_WHEN_IDLE_BIT (3)
|
||||
#define SECURITY_CAPABILITY_BIT (6)
|
||||
#define ALLOCATE_ADDRESS_BIT (7)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Valid values of the Association Status field
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.3.2.3
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MAC_ASSOCIATION_SUCCESSFUL = 0,
|
||||
MAC_PAN_AT_CAPACITY,
|
||||
MAC_PAN_ACCESS_DENIED
|
||||
} mac_association_status_t;
|
||||
|
||||
/**
|
||||
* @brief Capability information field
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.3.1.2.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t alternate_pan_coordinator : 1;
|
||||
uint8_t device_type : 1;
|
||||
uint8_t power_source : 1;
|
||||
uint8_t rx_on_when_idle : 1;
|
||||
uint8_t reserved : 2;
|
||||
uint8_t security_capability : 1;
|
||||
uint8_t allocate_address : 1;
|
||||
} mac_capability_t;
|
||||
|
||||
/**@brief The Alternate PAN Coordinator subfield of the Capability Information field. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_CAP_CANNOT_BE_PAN_COORD = 0, /**< Device is not capable of becoming
|
||||
the PAN coordinator.*/
|
||||
MAC_CAP_CAN_BE_PAN_COORD /**< Device is capable of becoming
|
||||
the PAN coordinator.*/
|
||||
} mac_cap_alt_pan_coord_t;
|
||||
|
||||
/**@brief The Device Type subfield of the Capability Information field. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_CAP_RFD_DEVICE = 0, /**< Device is an RFD.*/
|
||||
MAC_CAP_FFD_DEVICE /**< Device is an FFD.*/
|
||||
} mac_cap_device_type_t;
|
||||
|
||||
/**@brief The Power Source subfield of the Capability Information field. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_CAP_BATTERY_POWERED = 0, /**< Device is not AC-powered.*/
|
||||
MAC_CAP_MAINS_POWERED /**< Device is receiving power from the
|
||||
alternating current mains.*/
|
||||
} mac_cap_power_source_t;
|
||||
|
||||
/**@brief The Receiver On When Idle subfield of the Capability Information field. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_CAP_RX_OFF_WHEN_IDLE = 0, /**< Device conserves power during idle.*/
|
||||
MAC_CAP_RX_ON_WHEN_IDLE /**< Device does not disable its receiver
|
||||
to conserve power during idle periods.*/
|
||||
} mac_cap_rx_when_idle_t;
|
||||
|
||||
/**@brief The Security Capability subfield of the Capability Information field. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_CAP_CANNOT_SECURE = 0, /**< Device does not support securing.*/
|
||||
MAC_CAP_CAN_SECURE /**< Device is capable of sending and receiving
|
||||
cryptographically protected MAC frames.*/
|
||||
} mac_cap_secure_t;
|
||||
|
||||
/**@brief The Allocate Address subfield of the Capability Information field. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_CAP_SHORT_ADDR_NOT_REQ = 0, /**< The coordinator will not allocate a
|
||||
16-bit short address as a result of
|
||||
the association procedure.*/
|
||||
MAC_CAP_SHORT_ADDR_REQ /**< The coordinator will allocate a
|
||||
16-bit short address as a result of
|
||||
the association procedure.*/
|
||||
} mac_cap_allocate_addr_t;
|
||||
|
||||
#if (CONFIG_ASSOCIATE_REQ_ENABLED == 1)
|
||||
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE.confirm
|
||||
*
|
||||
* The MLME-ASSOCIATE.confirm primitive is generated by the initiating MLME and
|
||||
* issued to its next higher layer in response to an MLME-ASSOCIATE.request primitive.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.4.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint16_t assoc_short_address; /**< Association short 16-bit address. */
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_associate_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE.request.
|
||||
*
|
||||
* @details Allows a device to request an association with a coordinator.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.1.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirmation to this request. */
|
||||
mlme_associate_conf_t confirm;
|
||||
|
||||
/**
|
||||
* A total of 27 channels numbered 0 to 26.
|
||||
* are available per channel page (section 6.1.2.1).
|
||||
*/
|
||||
uint8_t logical_channel;
|
||||
|
||||
/**
|
||||
* A total of 32 channel pages are available
|
||||
* with channel pages 3 to 31 being reserved
|
||||
* for future use (section 6.1.2.2).
|
||||
*/
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
mac_addr_mode_t coord_addr_mode; /**< Coordinator address mode. */
|
||||
uint16_t coord_pan_id; /**< Coordinator PAN ID. */
|
||||
mac_addr_t coord_address; /**< Coordinator address. */
|
||||
mac_capability_t capability_information; /**< Capability information. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_associate_req_t;
|
||||
|
||||
|
||||
#if (CONFIG_ASSOCIATE_IND_ENABLED == 1)
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE.indication.
|
||||
*
|
||||
* @details The MLME-ASSOCIATE.indication primitive is generated by the MLME of
|
||||
* the coordinator and issued to its next higher layer to indicate the reception
|
||||
* of an association request command.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.2.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint64_t device_address; /**< 64-bit IEEE address. */
|
||||
uint8_t capability_information; /**< Capability information. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_associate_ind_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE.response.
|
||||
*
|
||||
* @details Generated by the next higher layer of a coordinator and issued
|
||||
* to its MLME in order to respond to the MLME-ASSOCIATE.indication primitive.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.3.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint64_t device_address; /**< 64-bit IEEE address. */
|
||||
uint16_t assoc_short_address; /**< Association short 16-bit address. */
|
||||
mac_association_status_t status; /**< Status of operation. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_associate_resp_t;
|
||||
|
||||
#endif // (CONFIG_ASSOCIATE_IND_ENABLED == 1)
|
||||
|
||||
/**
|
||||
* @brief Confirmation function.
|
||||
*
|
||||
* @details The MLME-ASSOCIATE.confirm primitive is generated by the
|
||||
* initiating MLME and issued to its next higher layer in response to
|
||||
* an MLME-ASSOCIATE.request primitive. If the request was successful,
|
||||
* the status parameter will indicate a successful association, as
|
||||
* contained in the Status field of the association response command.
|
||||
* Otherwise, the status parameter indicates either an error code from
|
||||
* the received association response command or the appropriate error
|
||||
* code from Table 50.
|
||||
* The status values are fully described in 7.1.3.1.3 and subclauses referenced by 7.1.3.1.3.
|
||||
*
|
||||
* @param Pointer to confirmation primitive.
|
||||
*/
|
||||
typedef void (* mlme_associate_conf_cb_t)(mlme_associate_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE request.
|
||||
*
|
||||
* @details Requests an association with a PAN through a coordinator
|
||||
* After request completion, user callback will be issued with
|
||||
* valid data stored in structure mlme_set_conf_t.
|
||||
*
|
||||
* @param req MLME_ASSOCIATE request structure.
|
||||
* @param conf_cb Pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.5
|
||||
*/
|
||||
void mlme_associate_req(mlme_associate_req_t * req, mlme_associate_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
#if (CONFIG_ASSOCIATE_IND_ENABLED == 1)
|
||||
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE indication handler.
|
||||
*
|
||||
* @details Indicates an association with a PAN through a coordinator
|
||||
* next higher layer of a coordinator receives the MLME-ASSOCIATE.indication
|
||||
* primitive to determine whether to accept or reject the unassociated device
|
||||
* using an algorithm outside the scope of standard.
|
||||
*
|
||||
* @param ind MLME ASSOCIATE indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.5.
|
||||
*/
|
||||
extern void mlme_associate_ind(mlme_associate_ind_t * ind);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ASSOCIATE response.
|
||||
*
|
||||
* @details Respond to an association with a PAN and issue to its MLME in order to
|
||||
* respond to the MLME-ASSOCIATE.indication.
|
||||
* Response structure passed as a parameter to this function must be retained
|
||||
* in memory until the related MLME-COMM-STATUS.indication is received.
|
||||
*
|
||||
* @param resp MLME_ASSOCIATE response structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.3.5.
|
||||
*/
|
||||
void mlme_associate_resp(mlme_associate_resp_t * resp);
|
||||
|
||||
#endif // (CONFIG_ASSOCIATE_IND_ENABLED == 1)
|
||||
|
||||
#endif // (CONFIG_ASSOCIATE_REQ_ENABLED == 1)
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_ASSOCIATE_H_INCLUDED
|
|
@ -0,0 +1,175 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_BEACON_NOTIFY_H_INCLUDED
|
||||
#define MAC_MLME_BEACON_NOTIFY_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_time.h"
|
||||
|
||||
/** @file
|
||||
* The MAC Beacon notify module declares the MAC beacon notification routine and necessary
|
||||
* types/macros according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_beacon_notify MAC MLME Beacon Notify API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Beacon Notify API.
|
||||
* @details The MAC Beacon Notify module declares Beacon Notify MLME routines and necessary macros/types
|
||||
* according to the MAC specification. MAC MLME Beacon notify indication is declared as
|
||||
* mlme_beacon_notify_ind().
|
||||
*/
|
||||
|
||||
/**@brief This constant is defined in 7.2.2.1.7 Address List field
|
||||
*
|
||||
* @details The maximum number of addresses pending shall be limited to seven and may comprise
|
||||
* both short and extended addresses.
|
||||
*/
|
||||
#define MAC_PENDING_ADDR_MAX 7
|
||||
|
||||
/*@brief The maximum length of GTS fields inside beacon in octets.
|
||||
*
|
||||
* @details This definition is used to allocate memory for outgoing beacon.
|
||||
*/
|
||||
#define MAC_MAX_GTS_FIELD_LEN 23
|
||||
|
||||
/**@brief Superframe specification structure.*/
|
||||
typedef struct
|
||||
{
|
||||
uint16_t beacon_order : 4;
|
||||
uint16_t superframe_order : 4;
|
||||
uint16_t final_cap_slot : 4;
|
||||
uint16_t battery_life_extension : 1;
|
||||
uint16_t reserved : 1;
|
||||
uint16_t pan_coordinator : 1;
|
||||
uint16_t association_permit : 1;
|
||||
} mac_superframe_spec_t;
|
||||
|
||||
|
||||
/** @brief List of pending addresses
|
||||
* Short addresses are at the top of the table.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_addr_t addr_list[MAC_PENDING_ADDR_MAX];
|
||||
/**< Addresses array. */
|
||||
uint8_t short_addr_number; /**< Number of short addresses in the array. */
|
||||
uint8_t ext_addr_number; /**< Number of long addresses in the array. */
|
||||
} mac_pending_addr_list_t;
|
||||
|
||||
/**@brief PAN Descriptor structure.
|
||||
*
|
||||
* @details See Table 55-Elements of PANDescriptor.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_addr_mode_t coord_addr_mode; /**< Coordinator addressing mode. */
|
||||
uint16_t coord_pan_id; /**< Coordinator PAN ID. */
|
||||
mac_addr_t coord_address; /**< Coordinator address. */
|
||||
uint8_t logical_channel; /**< Logical channel. */
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
mac_superframe_spec_t superframe_spec; /**< Superframe specification. */
|
||||
bool gts_permit; /**< Is GTS permitted? */
|
||||
uint8_t link_quality; /**< Link quality. */
|
||||
mac_timestamp_t timestamp; /**< Timestamp. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_failure; /**< Security failure. */
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mac_pan_descriptor_t;
|
||||
|
||||
|
||||
/**@brief Pending Address Specification
|
||||
*
|
||||
* @details See Figure 51-Format of the Pending Address Specification field.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t pending_short : 3;
|
||||
uint8_t : 1;
|
||||
uint8_t pending_extended : 3;
|
||||
uint8_t : 1;
|
||||
} mac_pend_addr_spec_t;
|
||||
|
||||
|
||||
/**@brief MLME-BEACON-NOTIFY.indication parameters
|
||||
*
|
||||
* @details See 7.1.5.1 MLME-BEACON-NOTIFY.indication
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t bsn; /**< Beacon sequence number. */
|
||||
mac_pan_descriptor_t pan_descriptor; /**< PAN descriptor. */
|
||||
mac_pend_addr_spec_t pend_addr_spec; /**< Pending address specification. */
|
||||
mac_addr_t addr_list[MAC_PENDING_ADDR_MAX];
|
||||
/**< Addresses array. */
|
||||
uint8_t sdu_length; /**< SDU length. */
|
||||
mac_payload_descriptor_t sdu; /**< SDU. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_beacon_notify_ind_t;
|
||||
|
||||
|
||||
/**@brief User implemented function, which handles MLME-BEACON-NOTIFY.indication.
|
||||
*
|
||||
* @details The MLME-BEACON-NOTIFY.indication primitive is used to send parameters contained
|
||||
* within a beacon frame received by the MAC sublayer to the next higher layer.
|
||||
* The primitive also sends a measure of the LQI and the time the beacon frame
|
||||
* was received. See 7.1.5.1 MLME-BEACON-NOTIFY.indication.
|
||||
*
|
||||
* @param ind MLME-BEACON-NOTIFY.indication parameters. See @ref mlme_beacon_notify_ind_t.
|
||||
*/
|
||||
extern void mlme_beacon_notify_ind(mlme_beacon_notify_ind_t * ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_BEACON_NOTIFY_H_INCLUDED
|
|
@ -0,0 +1,135 @@
|
|||
// Terms and conditions of usage are described in detail in NORDIC
|
||||
// SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
|
||||
//
|
||||
// Licensees are granted free, non-transferable use of the information. NO
|
||||
// WARRANTY of ANY KIND is provided. This heading must NOT be removed from
|
||||
// the file.
|
||||
|
||||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_COMM_STATUS_H_INCLUDED
|
||||
#define MAC_MLME_COMM_STATUS_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
|
||||
/** @file
|
||||
* The MAC Comm Status module declares the MAC communication status indication routine and
|
||||
* necessary types/macros according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_comm_status MAC MLME Comm Status API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Comm Status API.
|
||||
* @details The MAC Comm Status module declares communication status indication MLME routine and necessary
|
||||
* macros/types according to the MAC specification. MAC MLME Comm Status indication is declared as
|
||||
* mlme_comm_status_ind().
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MLME-COMM-STATUS.indication
|
||||
*
|
||||
* @details The MLME-COMM-STATUS.indication primitive allows the MLME to indicate a
|
||||
* communication status.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.12.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/**
|
||||
* The 16-bit PAN identifier of the device from which the frame was received or to
|
||||
* which the frame was being sent.
|
||||
*/
|
||||
uint16_t pan_id;
|
||||
|
||||
/**
|
||||
* The source addressing mode for this primitive. This value can take one of the
|
||||
* following values:
|
||||
* @ref mac_addr_mode_t
|
||||
* 0x00 = no address (addressing fields omitted).
|
||||
* 0x01 = reserved.
|
||||
* 0x02 = 16-bit short address.
|
||||
* 0x03 = 64-bit extended address.
|
||||
*/
|
||||
mac_addr_mode_t src_addr_mode;
|
||||
|
||||
/**
|
||||
* The individual device address of the entity from which the frame causing the error
|
||||
* originated.
|
||||
*/
|
||||
mac_addr_t src_addr;
|
||||
|
||||
/**
|
||||
* The destination addressing mode for this primitive.
|
||||
* According to 7.1.12.1.1, Table 69.
|
||||
*/
|
||||
mac_addr_mode_t dst_addr_mode;
|
||||
|
||||
/** The individual device address of the device for which the frame was intended. */
|
||||
mac_addr_t dst_addr;
|
||||
|
||||
/** The communications status. */
|
||||
mac_status_t status;
|
||||
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
} mlme_comm_status_ind_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-COMM-STATUS.indication handler
|
||||
*
|
||||
* @details The MLME-COMM-STATUS.indication primitive is generated by the MLME and issued to its next higher
|
||||
* layer either following a transmission instigated through a response primitive or on receipt of a frame that
|
||||
* generates an error in its security processing (see 7.5.8.2.3).
|
||||
*
|
||||
* @param ind MLME-COMM-STATUS.indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.12.1
|
||||
*/
|
||||
extern void mlme_comm_status_ind(mlme_comm_status_ind_t * ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_COMM_STATUS_H_INCLUDED
|
|
@ -0,0 +1,199 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_DISASSOCIATE_H_INCLUDED
|
||||
#define MAC_MLME_DISASSOCIATE_H_INCLUDED
|
||||
|
||||
#if (CONFIG_DISASSOCIATE_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Disassociate module declares the MAC disassociation routines and
|
||||
* necessary types/macros according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_diassociate MAC MLME Disassociate API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Disassociate API.
|
||||
* @details The MLME Disassociation module declares Disassociation MAC routines and necessary types
|
||||
* according to the MAC specification. More specifically, MLME Disassociation request aka
|
||||
* mlme_disassociate_req(), MLME Disassociation confirm callback typedef aka
|
||||
* mlme_disassociate_conf_cb_t, and MLME Disassociation indication as mlme_disassociate_ind()
|
||||
* primitives are declared.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MAC Disassociation Reason field
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.3.2.2
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
/** The coordinator wishes the device to leave the PAN. */
|
||||
MAC_COORD_REASON = 1,
|
||||
/** The device wishes to leave the PAN. */
|
||||
MAC_DEV_REASON = 2
|
||||
} mac_disassociate_reason_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-DISASSOCIATE.confirm
|
||||
*
|
||||
* @details On receipt of the MLME-DISASSOCIATE.confirm primitive, the next
|
||||
* higher layer of the initiating device is notified of the result of the
|
||||
* disassociation attempt. If the disassociation attempt was successful,
|
||||
* the status parameter will be set to SUCCESS. Otherwise, the status parameter
|
||||
* indicates the error.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.4.3
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
mac_addr_mode_t device_addr_mode; /**< Device addressing mode. */
|
||||
uint16_t device_pan_id; /**< Device PAN ID. */
|
||||
mac_addr_t device_address; /**< Device address. */
|
||||
} mlme_disassociate_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-DISASSOCIATE.request
|
||||
*
|
||||
* @details The MLME-DISASSOCIATE.request primitive is generated by the next
|
||||
* higher layer of an associated device and issued to its MLME to request
|
||||
* disassociation from the PAN. It is also generated by the next higher layer
|
||||
* of the coordinator and issued to its MLME to instruct an
|
||||
* associated device to leave the PAN.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.4.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_disassociate_conf_t confirm;
|
||||
|
||||
mac_addr_mode_t device_addr_mode; /**< Device addressing mode. */
|
||||
uint16_t device_pan_id; /**< Device PAN ID. */
|
||||
mac_addr_t device_address; /**< Device address. */
|
||||
mac_disassociate_reason_t disassociate_reason; /**< Disassociation reason. */
|
||||
bool tx_indirect; /**< Is TX indirect? */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_disassociate_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-DISASSOCIATE.indication
|
||||
*
|
||||
* @details Is generated by the MLME and issued to its next higher
|
||||
* layer on receipt of a disassociation notification command.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.4.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint64_t device_address; /**< Device address. */
|
||||
mac_disassociate_reason_t disassociate_reason; /**< Disassociation reason. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_disassociate_ind_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Customer's function of confirmation
|
||||
*
|
||||
* @details The MLME-DISASSOCIATE.confirm primitive is generated by the initiating
|
||||
* MLME and issued to its next higher layer in response to an MLME-DISASSOCIATE.request
|
||||
* primitive. This primitive returns a status of either SUCCESS, indicating that the
|
||||
* disassociation request was successful, or the appropriate error code.
|
||||
* The status values are fully described in 7.1.4.1.3 and subclauses referenced by 7.1.4.1.3.
|
||||
*
|
||||
* @param pointer to confirmation primitive
|
||||
*/
|
||||
typedef void (* mlme_disassociate_conf_cb_t)(mlme_disassociate_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-DISASSOCIATE request
|
||||
*
|
||||
* @details Request disassociation with a PAN
|
||||
* After request completion, user callback will be issued with
|
||||
* valid data stored in structure @ref mlme_disassociate_conf_t.
|
||||
*
|
||||
* @param req MLME_DISASSOCIATE request structure.
|
||||
* @param conf_cb pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.4.4
|
||||
*/
|
||||
void mlme_disassociate_req(mlme_disassociate_req_t * req, mlme_disassociate_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-DISASSOCIATE indication handler
|
||||
*
|
||||
* @details Indicates an disassociation with a PAN
|
||||
*
|
||||
* @param ind MLME_DISASSOCIATE indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.4.4
|
||||
*/
|
||||
extern void mlme_disassociate_ind(mlme_disassociate_ind_t * ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_DISASSOCIATE_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MLME_DISASSOCIATE_H_INCLUDED
|
|
@ -0,0 +1,211 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_GTS_H_INCLUDED
|
||||
#define MAC_MLME_GTS_H_INCLUDED
|
||||
|
||||
#if (CONFIG_GTS_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME GTS module declares the MAC Guaranteed time slots routines and
|
||||
* necessary types/macros according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_gts MAC MLME GTS API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME GTS API.
|
||||
* @details The MAC GTS module declares MAC Guaranteed Time Slots routines and necessary types according to
|
||||
* the MAC specification. More specifically, MLME GTS request aka mlme_gts_req(), MLME GTS indicaton
|
||||
* aka mlme_gts_ind(), and MLME GTS confirm callback typedef aka mlme_gts_conf_cb_t primitives are
|
||||
* declared.
|
||||
*/
|
||||
|
||||
/**@brief GTS directions, from device side. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_GTS_DIR_TXONLY = 0, /**< TX only direction. */
|
||||
MAC_GTS_DIR_RXONLY = 1 /**< RX only direction. */
|
||||
} mac_gts_direction_t;
|
||||
|
||||
|
||||
/**@brief GTS characteristics type. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_GTS_DEALLOC = 0, /**< GTS Dealloc. */
|
||||
MAC_GTS_ALLOC = 1 /**< GTS Alloc. */
|
||||
} mac_gts_characteristics_type_t;
|
||||
|
||||
|
||||
/**@brief MAC GTS characteristics (not packed)
|
||||
*
|
||||
* @details See Section 7.3.9.2
|
||||
*/
|
||||
typedef union
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint8_t gts_length : 4;
|
||||
uint8_t gts_direction : 1;
|
||||
uint8_t characterictics_type : 1;
|
||||
uint8_t : 2;
|
||||
} bit;
|
||||
uint8_t all;
|
||||
} mac_gts_characteristics_t;
|
||||
|
||||
/**
|
||||
* @brief MLME-GTS.confirm
|
||||
*
|
||||
* @details The MLME-GTS.confirm primitive reports the results of a
|
||||
* request to allocate a new GTS or deallocate an existing GTS.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_gts_characteristics_t gts_characteristics; /**< GTS characteristics. */
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
} mlme_gts_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GTS.request
|
||||
*
|
||||
* @details The MLME-GTS.request primitive allows a device to send a request
|
||||
* to the PAN coordinator to allocate a new GTS or to deallocate an existing GTS.
|
||||
* This primitive is also used by the PAN coordinator to initiate a GTS deallocation.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_gts_conf_t confirm;
|
||||
|
||||
mac_gts_characteristics_t gts_characteristics; /**< GTS characteristics. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_gts_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GTS.indication
|
||||
*
|
||||
* @details The MLME-GTS.indication primitive indicates that a
|
||||
* GTS has been allocated or that a previously allocated GTS
|
||||
* has been deallocated.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.3
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint16_t device_address; /**< Device address. */
|
||||
mac_gts_characteristics_t gts_characteristics; /**< GTS characteristics. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_gts_ind_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GTS confirm callback
|
||||
*
|
||||
* @details The MLME-GTS.confirm primitive is generated by the MLME and
|
||||
* issued to its next higher layer in response to a previously
|
||||
* issued MLME-GTS.request primitive.
|
||||
*
|
||||
* @param MLME_GTS callback structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.4
|
||||
*/
|
||||
typedef void (* mlme_gts_conf_cb_t)(mlme_gts_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GTS request
|
||||
*
|
||||
* @details The MLME-GTS.request primitive is generated by the next higher
|
||||
* layer of a device and issued to its MLME to request the allocation of a
|
||||
* new GTS or to request the deallocation of an existing GTS. It is also
|
||||
* generated by the next higher layer of the PAN coordinator and issued to
|
||||
* its MLME to request the deallocation of an existing GTS.
|
||||
*
|
||||
* @param req MLME_GTS request structure.
|
||||
* @param conf_cb pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.4
|
||||
*/
|
||||
void mlme_gts_req(mlme_gts_req_t * req, mlme_gts_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GTS indication handler
|
||||
*
|
||||
* @details The MLME-GTS.indication primitive is generated by the MLME of
|
||||
* the PAN coordinator to its next higher layer whenever a GTS is allocated
|
||||
* or deallocated following the reception of a GTS request command (see 7.3.9)
|
||||
* by the MLME. The MLME of the PAN coordinator also generates this primitive when a GTS
|
||||
* deallocation is initiated by the PAN coordinator itself.
|
||||
*
|
||||
* @param ind MLME_GTS indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.4
|
||||
*/
|
||||
extern void mlme_gts_ind(mlme_gts_ind_t * ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_GTS_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MLME_GTS_H_INCLUDED
|
|
@ -0,0 +1,151 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_ORPHAN_H_INCLUDED
|
||||
#define MAC_MLME_ORPHAN_H_INCLUDED
|
||||
|
||||
#if (CONFIG_ORPHAN_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "mac_common.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Orphan module declares the MAC Orphan routines and
|
||||
* necessary types/macros according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_orphan MAC MLME Orphan API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Orphan API.
|
||||
* @details The MAC Orphan module declares routines and necessary types to deal with the Orphan devices
|
||||
* according to the MAC specification. More specifically, MAC MLME Orphan indication aka
|
||||
* mlme_orphan_ind(), MAC MLME Orphan response aka mlme_orphan_resp() primitives are declared.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MLME-ORPHAN.indication
|
||||
*
|
||||
* @details The MLME-ORPHAN.indication primitive allows the MLME of a coordinator
|
||||
* to notify the next higher layer of the presence of an orphaned device.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.8.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** The address of the orphaned device. */
|
||||
uint64_t orphan_address;
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_orphan_ind_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ORPHAN.response
|
||||
*
|
||||
* @details The MLME-ORPHAN.response primitive allows the next higher layer of a coordinator
|
||||
* to respond to the MLME-ORPHAN.indication primitive.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.8.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** The address of the orphaned device. */
|
||||
uint64_t orphan_address;
|
||||
|
||||
/**
|
||||
* The 16-bit short address allocated to the orphaned device if it is associated with this
|
||||
* coordinator. The special short address 0xfffe indicates that no short address was
|
||||
* allocated, and the device will use its 64-bit extended address in all communications.
|
||||
* If the device was not associated with this coordinator, this field will contain the
|
||||
* value 0xffff and be ignored on receipt.
|
||||
*/
|
||||
uint16_t short_address;
|
||||
|
||||
/** TRUE if the orphaned device is associated with this coordinator or FALSE otherwise. */
|
||||
bool associated_member;
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_orphan_resp_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ORPHAN.indication handler
|
||||
*
|
||||
* @details The MLME-ORPHAN.indication primitive is generated by the MLME of a coordinator
|
||||
* and issued to its next higher layer on receipt of an orphan notification command (see 7.3.6).
|
||||
*
|
||||
* @param ind MLME-ORPHAN.indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.8.1
|
||||
*/
|
||||
extern void mlme_orphan_ind(mlme_orphan_ind_t * ind);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-ORPHAN.response handler
|
||||
*
|
||||
* @details The MLME-ORPHAN.response primitive is generated by the next higher layer and issued to its MLME
|
||||
* when it reaches a decision about whether the orphaned device indicated in the MLME-ORPHAN.indication
|
||||
* primitive is associated.
|
||||
*
|
||||
* @param resp MLME-ORPHAN.response structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.8.2
|
||||
*/
|
||||
void mlme_orphan_resp(mlme_orphan_resp_t * resp);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_ORPHAN_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MLME_ORPHAN_H_INCLUDED
|
|
@ -0,0 +1,508 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_PIB_H_INCLUDED
|
||||
#define MAC_MLME_PIB_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "phy_plme_pib.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
#include "mac_security.h"
|
||||
#include "sys_debug.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME PIB module declares the MAC PHY Information Base routines and
|
||||
* necessary types/macros according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_pib MAC MLME PIB API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME PIB API.
|
||||
* @details The MAC PIB module declares routines and necessary types to deal with the PHY Information Base
|
||||
* functionality related to MAC. More specifically, MLME PIB Get request aka mlme_get_req(), MLME
|
||||
* PIB Set request aka mlme_set_req(), MLME PIB confirmation callbacks aka mlme_get_conf_cb_t, and
|
||||
* mlme_set_conf_cb_t primitives are declared. Two additional primitives not covered by the
|
||||
* standard are declared. These are mlme_get() and mlme_set() which are synchronous versions of
|
||||
* mlme_get_req() and mlme_set_req() accordingly. There is one helper informational routine
|
||||
* mlme_pib_attr_size_calc() to count MLME attribute size in bytes. Refer to the
|
||||
* mac_pib_param_test application for detailed samples of implementation of these primitives.
|
||||
* This module also defines the MAC Table API. The tables can be used to deal with MAC attributes.
|
||||
* A special initialization routine mac_table_init() should be called before using of any other MAC
|
||||
* table API. The mac_table_reset() routine is used to clean up an existing (initialized) table.
|
||||
* mac_table_idx_get() searches through a MAC table to find the item with requested idx. The
|
||||
* mac_table_item_set() routine is needed to substitute a table item with a new value. The
|
||||
* mac_table_item_remove() routine removes the item with the given index from the table and
|
||||
* frees all resources associated with the item. mac_table_item_front() and mac_table_item_next()
|
||||
* return the first and next item from the table. The mac_table_size_get() routine returns the
|
||||
* number of items in the table, while mac_table_is_empty() checks if the table is empty.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MAC PIB attribute identifiers
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.4.2
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MAC_ACK_WAIT_DURATION = 0x40,
|
||||
MAC_ASSOCIATION_PERMIT,
|
||||
MAC_AUTO_REQUEST,
|
||||
MAC_BATT_LIFE_EXT,
|
||||
MAC_BATT_LIFE_EXT_PERIODS,
|
||||
MAC_BEACON_PAYLOAD, /* 0x45 */
|
||||
MAC_BEACON_PAYLOAD_LENGTH,
|
||||
MAC_BEACON_ORDER, /**< Specification of how often the
|
||||
coordinator transmits its
|
||||
beacon. If BO = 15, the
|
||||
coordinator will not transmit
|
||||
a periodic beacon.*/
|
||||
MAC_BEACON_TX_TIME,
|
||||
MAC_BSN,
|
||||
MAC_COORD_EXTENDED_ADDRESS, /* 0x4A */
|
||||
MAC_COORD_SHORT_ADDRESS,
|
||||
MAC_DSN,
|
||||
MAC_GTS_PERMIT,
|
||||
MAC_MAX_CSMA_BACKOFFS,
|
||||
MAC_MIN_BE,
|
||||
MAC_PAN_ID, /**< PAN Identifier.*/
|
||||
/* 0x50 */
|
||||
MAC_PROMISCUOUS_MODE,
|
||||
MAC_RX_ON_WHEN_IDLE,
|
||||
MAC_SHORT_ADDRESS, /**< MAC Short Address.*/
|
||||
MAC_SUPERFRAME_ORDER,
|
||||
MAC_TRANSACTION_PERSISTENCE_TIME, /* 0x55 */
|
||||
MAC_ASSOCIATED_PAN_COORD,
|
||||
MAC_MAX_BE,
|
||||
MAC_MAX_FRAME_TOTAL_WAIT_TIME,
|
||||
MAC_MAX_FRAME_RETRIES,
|
||||
MAC_RESPONSE_WAIT_TIME, /* 0x5A */
|
||||
MAC_SYNC_SYMBOL_OFFSET,
|
||||
MAC_TIMESTAMP_SUPPORTED,
|
||||
MAC_SECURITY_ENABLED,
|
||||
MAC_MIN_LIFS_PERIOD, /* 0x5E No attribute id in Table 86.*/
|
||||
MAC_MIN_SIFS_PERIOD, /* 0x5F No attribute id in Table 86.*/
|
||||
MAC_EXTENDED_ADDRESS, /**< MAC Extended Address.*/
|
||||
/* 0x60 Not covered by standard.*/
|
||||
MAC_IS_PAN_COORD,
|
||||
|
||||
#if (CONFIG_SECURE == 1)
|
||||
MAC_KEY_TABLE = 0x71,
|
||||
MAC_KEY_TABLE_ENTRIES,
|
||||
MAC_DEVICE_TABLE,
|
||||
MAC_DEVICE_TABLE_ENTRIES,
|
||||
MAC_SECURITY_LEVEL_TABLE, /* 0x75 */
|
||||
MAC_SECURITY_LEVEL_TABLE_ENTRIES,
|
||||
MAC_FRAME_COUNTER,
|
||||
MAC_AUTO_REQUEST_SECURITY_LEVEL,
|
||||
MAC_AUTO_REQUEST_KEY_ID_MODE,
|
||||
MAC_AUTO_REQUEST_KEY_SOURCE, /* 0x7A */
|
||||
MAC_AUTO_REQUEST_KEY_INDEX,
|
||||
MAC_DEFAULT_KEY_SOURCE,
|
||||
MAC_PAN_COORD_EXTENDED_ADDRESS,
|
||||
MAC_PAN_COORD_SHORT_ADDRESS,
|
||||
|
||||
/* Items below do not covered by the standard */
|
||||
|
||||
// these three IDs are used to make access to the root of security tables
|
||||
MAC_KEY_TABLE_POINTER,
|
||||
MAC_DEVICE_TABLE_POINTER,
|
||||
MAC_SECURITY_LEVEL_TABLE_POINTER,
|
||||
|
||||
// these three IDs are stored inside PIB base and
|
||||
// used to get table item sizes
|
||||
MAC_KEY_ID_LOOKUP_LIST,
|
||||
MAC_KEY_DEVICE_LIST,
|
||||
MAC_KEY_USAGE_LIST,
|
||||
#endif
|
||||
} mlme_pib_attr_id_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief United PIB attribute identifiers
|
||||
*
|
||||
* To unite access to MAC and PHY PIB by one API
|
||||
*/
|
||||
typedef union
|
||||
{
|
||||
mlme_pib_attr_id_t mlme_id; /**< PIB is MAC-based. */
|
||||
plme_pib_attr_id_t plme_id; /**< PIB is PHY-based. */
|
||||
} pib_id_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GET.confirm
|
||||
*
|
||||
* @details structure for confirming information about a given PIB attribute.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.6.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
pib_id_t pib_attribute; /**< PIB Attribute. */
|
||||
uint8_t pib_attribute_idx; /**< PIB Attribute index. */
|
||||
/** value size is calculated with 'mlme_pib_attr_size_calc' */
|
||||
uint8_t * value; /**< Attribute value. */
|
||||
} mlme_get_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GET.request
|
||||
*
|
||||
* @details structure for requesting information about a given PIB attribute.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.6.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_get_conf_t confirm;
|
||||
|
||||
pib_id_t pib_attribute; /**< PIB Attribute. */
|
||||
uint8_t pib_attribute_idx; /**< PIB Attribute index. */
|
||||
} mlme_get_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-SET.confirm
|
||||
*
|
||||
* @details structure for reporting the results of an attempt to write a value
|
||||
* to a PIB attribute.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.13.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
pib_id_t pib_attribute; /**< PIB Attribute. */
|
||||
uint8_t pib_attribute_idx; /**< PIB Attribute index. */
|
||||
} mlme_set_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-SET.request
|
||||
*
|
||||
* @details structure for setting a PIB attribute.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.13.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_set_conf_t confirm;
|
||||
|
||||
pib_id_t pib_attribute; /**< PIB Attribute. */
|
||||
uint8_t pib_attribute_idx; /**< PIB Attribute index. */
|
||||
uint8_t * value; /**< Attribute value. The value size is calculated
|
||||
with mlme_pib_attr_size_calc. */
|
||||
} mlme_set_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Customer's function of confirmation
|
||||
*
|
||||
* @details The MLME-GET.confirm primitive is generated by the MLME and issued
|
||||
* to its next higher layer in response to an MLME-GET.request primitive.
|
||||
* This primitive returns a status of either SUCCESS, indicating that the request
|
||||
* to read a PIB attribute was successful, or an error code of UNSUPPORTED_ATTRIBUTE.
|
||||
* When an error code of UNSUPPORTED_ATTRIBUTE is returned, the PIBAttribute value
|
||||
* parameter will be set to length zero. The status values are fully described in 7.1.6.1.3.
|
||||
*
|
||||
* @param pointer to confirmation primitive
|
||||
*/
|
||||
typedef void (* mlme_get_conf_cb_t)(mlme_get_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Customer's function of confirmation
|
||||
*
|
||||
* @details The MLME-SET.confirm primitive is generated by the MLME and issued to its
|
||||
* next higher layer in response to an MLME-SET.request primitive. The MLME-SET.confirm
|
||||
* primitive returns a status of either SUCCESS, indicating that the requested value was
|
||||
* written to the indicated PIB attribute, or the appropriate error code.
|
||||
* The status values are fully described in 7.1.13.1.3.
|
||||
*
|
||||
* @param pointer to confirmation primitive
|
||||
*/
|
||||
typedef void (* mlme_set_conf_cb_t)(mlme_set_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-GET request
|
||||
*
|
||||
* @details Request information about a given PIB attribute.
|
||||
*
|
||||
* @param[in] req pointer to request structure.
|
||||
* @param[in] conf_cb pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.6.
|
||||
* See \a mlme_get() for more details.
|
||||
*/
|
||||
void mlme_get_req(mlme_get_req_t * req, mlme_get_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-SET request
|
||||
*
|
||||
* @details Request to set a PIB attribute.
|
||||
* After request completion, user callback will be issued with
|
||||
* valid data stored in structure @ref mlme_set_conf_t.
|
||||
*
|
||||
* See \a mlme_set() for more details.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.13
|
||||
*
|
||||
* @param[in] req MLME_SET request structure.
|
||||
* @param[in] conf_cb pointer to user callback.
|
||||
*/
|
||||
void mlme_set_req(mlme_set_req_t * req, mlme_set_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Counts MLME attribute size
|
||||
*
|
||||
* @details This is an implementation-specific function not covered by the standard.
|
||||
*
|
||||
* @param[in] id attribute id.
|
||||
* @param[in] idx index inside the table in case the attribute is a table.
|
||||
*
|
||||
* @return size of attribute in bytes.
|
||||
*/
|
||||
size_t mlme_pib_attr_size_calc(pib_id_t id, uint8_t idx);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Gets parameters from PIB directly (without request - confirm approach)
|
||||
*
|
||||
* @details Optional. Not covered by a standard.
|
||||
*
|
||||
* For non-tabled attributes this function will return value to location
|
||||
* passed to the last argument.
|
||||
*
|
||||
* For tabled attributes this function will return pointer to
|
||||
* a descriptor structure of corresponding table.
|
||||
*
|
||||
* @param[in] id attribute id.
|
||||
* @param[in] idx index inside the table in case the attribute is a table.
|
||||
* @param[out] mem either pointer to memory where attribute value is returned
|
||||
* (for all attributes except MAC_KEY_TABLE, MAC_DEVICE_TABLE,
|
||||
* MAC_SECURITY_LEVEL_TABLE), or pointer to memory where pointer
|
||||
* to attribute storage place is returned.
|
||||
*
|
||||
* @return status of operation
|
||||
*/
|
||||
mac_status_t mlme_get(pib_id_t id, uint8_t idx, void * mem);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Sets parameters to PIB directly (without request - confirm approach)
|
||||
*
|
||||
* @details Optional. Not covered by a standard.
|
||||
*
|
||||
* This function performs copying or replacement of some attribute value
|
||||
* into the PIB base memory.
|
||||
*
|
||||
* Note, that all security tables are copied into dynamic memory, that
|
||||
* mlme_set is responsible to allocate. For nested tables copying is done
|
||||
* in a shallow manner (in Python sense). It means that passed \a mac_key_descr_t
|
||||
* is copied as-is, without creating copies of internal tables.
|
||||
* Caller must allocate and prepare all nested tables such as
|
||||
* #MAC_KEY_DEVICE_LIST, #MAC_KEY_ID_LOOKUP_LIST and #MAC_KEY_USAGE_LIST
|
||||
* before calling this function.
|
||||
*
|
||||
* Passed attribute value will replace the current one, if the item with such
|
||||
* \a id and \a idx already exists. This function is responsible for
|
||||
* freeing all items during destruction of existing objects.
|
||||
*
|
||||
* @note Nested tables may be expanded and reduced with \a mac_table_item_set()
|
||||
* and other similar functions.
|
||||
*
|
||||
* @param[in] id attribute id.
|
||||
* @param[in] idx index inside the table in case the attribute is a table.
|
||||
* @param[out] mem pointer to memory for parameter storing.
|
||||
*
|
||||
* @return status of operation
|
||||
*/
|
||||
mac_status_t mlme_set(pib_id_t id, uint8_t idx, void * mem);
|
||||
|
||||
|
||||
#if (CONFIG_SECURE == 1)
|
||||
/**
|
||||
* @brief Initializes a table. This function MUST be called before accessing
|
||||
* to a newly allocated table.
|
||||
*
|
||||
* @param[out] p_table Pointer to a fresh table.
|
||||
*/
|
||||
void mac_table_init(mac_table_t * p_table);
|
||||
|
||||
/**
|
||||
* @brief Resets a table, freeing all its elements.
|
||||
*
|
||||
* @param[in] p_table Pointer to the table to reset.
|
||||
* @param[in] id One of #MAC_KEY_TABLE, #MAC_DEVICE_TABLE, #MAC_SECURITY_LEVEL_TABLE,
|
||||
* #MAC_KEY_ID_LOOKUP_LIST, #MAC_KEY_DEVICE_LIST, #MAC_KEY_USAGE_LIST to let
|
||||
* function know about the size of p_item.
|
||||
*/
|
||||
void mac_table_reset(mac_table_t * p_table, mlme_pib_attr_id_t id);
|
||||
|
||||
/**
|
||||
* @brief Searches through mac_table_t and finds the item with requested idx.
|
||||
*
|
||||
* @param[in] p_table Table to search through.
|
||||
* @param[in] idx Item idx to match.
|
||||
*
|
||||
* @return Pointer to mac_table_item_t with requested idx or NULL if such
|
||||
* an item cannot be found.
|
||||
*/
|
||||
mac_table_item_t * mac_table_idx_get(const mac_table_t * p_table, uint8_t idx);
|
||||
|
||||
/**
|
||||
* @brief Sets new value item for mac_table_t.
|
||||
*
|
||||
* @param[out] p_table Pointer to the table to add item to.
|
||||
* @param[in] p_item Pointer to a new item. This item must include appropriate idx
|
||||
* (less than the maximum table size).
|
||||
* @param[in] id One of #MAC_KEY_TABLE, #MAC_DEVICE_TABLE, #MAC_SECURITY_LEVEL_TABLE,
|
||||
* #MAC_KEY_ID_LOOKUP_LIST, #MAC_KEY_DEVICE_LIST, #MAC_KEY_USAGE_LIST to let
|
||||
* function know about the size of p_item.
|
||||
* @param[in] idx Item index inside the selected table.
|
||||
*
|
||||
* @details This function performs a "deep copy" of passed table item to conform with
|
||||
* mlme_set behavior. New copy resides in the heap memory. If an item with requested
|
||||
* idx has been already set earlier, this function frees the old item and pushes
|
||||
* a new one instead.
|
||||
*
|
||||
* @retval #MAC_INVALID_INDEX if idx exceeds allowed maximum number of items in
|
||||
* the table.
|
||||
* @retval #MAC_LIMIT_REACHED if there is no enough dynamic memory to put this item
|
||||
* into the security table.
|
||||
* @retval #MAC_SUCCESS if insertion has been performed successfully.
|
||||
*/
|
||||
mac_status_t mac_table_item_set(mac_table_t * p_table,
|
||||
const mac_table_item_t * p_item,
|
||||
mlme_pib_attr_id_t id,
|
||||
uint8_t idx);
|
||||
|
||||
/**
|
||||
* @brief Removes an item from a mac_table_t instance and frees all resources,
|
||||
* associated with this item.
|
||||
*
|
||||
* @param[out] p_table Pointer to the table to remove item from.
|
||||
* @param[in] id One of #MAC_KEY_TABLE, #MAC_DEVICE_TABLE, #MAC_SECURITY_LEVEL_TABLE,
|
||||
* #MAC_KEY_ID_LOOKUP_LIST, #MAC_KEY_DEVICE_LIST, #MAC_KEY_USAGE_LIST to let
|
||||
* function perform down-casting correctly.
|
||||
* @param[in] idx Item index inside of selected table.
|
||||
*
|
||||
* @retval #MAC_INVALID_INDEX if passed index is not found in the table or exceeds
|
||||
* the allowed maximum.
|
||||
* @retval #MAC_SUCCESS if no errors happen during removing.
|
||||
*/
|
||||
mac_status_t mac_table_item_remove(mac_table_t * p_table,
|
||||
mlme_pib_attr_id_t id,
|
||||
uint8_t idx);
|
||||
|
||||
/**
|
||||
* @brief Gets first available item from a table.
|
||||
*
|
||||
* @details This function might be used along with \a mac_table_item_next to
|
||||
* search through some table.
|
||||
*
|
||||
* @param[in] p_table Pointer to a MAC table.
|
||||
*
|
||||
* @return Pointer to the first table item or NULL if the table is empty.
|
||||
*/
|
||||
mac_table_item_t * mac_table_item_front(const mac_table_t * p_table);
|
||||
|
||||
/**
|
||||
* @brief Returns the next available item in table.
|
||||
*
|
||||
* @details MAC tables are stored unsorted in memory, so there is no guarantee that
|
||||
* index of the next item is always greater or smaller than the current one.
|
||||
* Items are not stored in chronological order either.
|
||||
*
|
||||
* @param[in] p_table Pointer to a table to select item from.
|
||||
* @param[in] p_current_item Pointer to the current item.
|
||||
*
|
||||
* @return Pointer to the next item in table or NULL, if the item is the last one.
|
||||
*/
|
||||
mac_table_item_t * mac_table_item_next(const mac_table_t * p_table,
|
||||
const mac_table_item_t * p_current_item);
|
||||
|
||||
/**
|
||||
* @brief Gets number of items used inside mac_table_t.
|
||||
*
|
||||
* @param[in] p_table Pointer to interested table.
|
||||
*
|
||||
* @return 8-bit integer equal to number of items inside the table that have
|
||||
* been set at least once.
|
||||
*/
|
||||
static inline uint8_t mac_table_size_get(const mac_table_t * p_table)
|
||||
{
|
||||
ASSERT(p_table != NULL);
|
||||
|
||||
return p_table->size;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function checks if a MAC table is empty.
|
||||
*
|
||||
* @param[in] p_table Pointer to a MAC table.
|
||||
*
|
||||
* @return true if there are no items inside table, false otherwise.
|
||||
*/
|
||||
static inline bool mac_table_is_empty(const mac_table_t * p_table)
|
||||
{
|
||||
ASSERT(p_table != NULL);
|
||||
|
||||
return sys_queue_is_empty(&p_table->queue);
|
||||
}
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_PIB_H_INCLUDED
|
|
@ -0,0 +1,151 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_POLL_H_INCLUDED
|
||||
#define MAC_MLME_POLL_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Poll module declares the MAC Poll primitives and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_poll MAC MLME Poll API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Poll API.
|
||||
* @details The MAC Poll module declares MLME Poll primitives and necessary types according to
|
||||
* the MAC specification. More specifically, MLME Poll request aka mlme_poll_req(), MLME Poll
|
||||
* indicaton aka mlme_poll_ind(), and MLME Poll confirm callback typedef aka mlme_poll_conf_cb_t
|
||||
* primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief MLME-POLL.confirm
|
||||
*
|
||||
* @details The MLME-POLL.confirm primitive reports the results of a request
|
||||
* to poll the coordinator for data.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.16.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
} mlme_poll_conf_t;
|
||||
|
||||
|
||||
/**@brief MLME-POLL.request
|
||||
*
|
||||
* @details The MLME-POLL.request primitive prompts the device
|
||||
* to request data from the coordinator.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.16.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_poll_conf_t confirm;
|
||||
|
||||
mac_addr_mode_t coord_addr_mode; /**< Coordinator address mode. */
|
||||
uint16_t coord_pan_id; /**< Coordinator PAN ID. */
|
||||
mac_addr_t coord_address; /**< Coordinator address. */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_poll_req_t;
|
||||
|
||||
/** @brief MLME-Poll.indication
|
||||
*
|
||||
* @details The MLME-POLL.indication primitive indicates the reception
|
||||
* of a Data request command frame by the MAC sub-layer and issued to
|
||||
* the local SSCS (service specific convergence sublayer).
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_addr_mode_t src_addr_mode; /**< Source address mode. */
|
||||
mac_addr_t src_address; /**< Source address. */
|
||||
} mlme_poll_ind_t;
|
||||
|
||||
|
||||
/**@brief Prototype of the user-implemented MLME-POLL.confirm callback function.
|
||||
*
|
||||
* @details The MLME-POLL.confirm primitive is generated by the MLME and issued
|
||||
* to its next higher layer in response to an MLME-POLL.request primitive.
|
||||
* If the request was successful, the status parameter will be equal to SUCCESS,
|
||||
* indicating a successful poll for data. Otherwise, the status parameter indicates the
|
||||
* appropriate error code. The status values are fully described in 7.1.16.1.3 and
|
||||
* the subclauses referenced by 7.1.16.1.3.
|
||||
*
|
||||
* @param pointer to a confirmation primitive.
|
||||
*/
|
||||
typedef void (* mlme_poll_conf_cb_t)(mlme_poll_conf_t *);
|
||||
|
||||
|
||||
/**@brief MLME-POLL.request
|
||||
*
|
||||
* @details The MLME-POLL.request primitive is generated by the next higher layer and
|
||||
* issued to its MLME when data are to be requested from a coordinator.
|
||||
*
|
||||
* @param[in] req MLME-POLL.request parameters
|
||||
* @param[in] conf_cb User-implemented callback function, which will be
|
||||
* called by MLME in order to pass MLME-POLL.confirm to the user.
|
||||
*/
|
||||
void mlme_poll_req(mlme_poll_req_t * req, mlme_poll_conf_cb_t conf_cb);
|
||||
|
||||
/**@brief MLME-POLL.indication
|
||||
*
|
||||
* @details The MLME-Poll.indication primitive notifies the next higher level that
|
||||
* a request for data has been received.
|
||||
*
|
||||
* @param[in] p_ind pointer to a poll indication structure
|
||||
*/
|
||||
extern void mlme_poll_ind(mlme_poll_ind_t * p_ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_POLL_H_INCLUDED
|
|
@ -0,0 +1,125 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_RESET_H_INCLUDED
|
||||
#define MAC_MLME_RESET_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Reset module declares the MAC Reset primitives and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_reset MAC MLME Reset API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Reset API.
|
||||
* @details The MAC Reset module declares MLME Reset primitives and necessary types according to
|
||||
* the MAC specification. More specifically, MLME Reset request aka mlme_reset_req(), and MLME
|
||||
* Reset confirm callback typedef aka mlme_reset_conf_cb_t primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief MLME-Reset.confirm
|
||||
*
|
||||
* @details The MLME-Reset.confirm primitive reports the results of a request
|
||||
* to reset MAC layer of the device.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.9.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
} mlme_reset_conf_t;
|
||||
|
||||
/**@brief MLME-RESET.request
|
||||
*
|
||||
* @details The MLME-RESET.request primitive allows the next
|
||||
* higher layer to request that the MLME performs a reset operation.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.9.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_reset_conf_t confirm;
|
||||
|
||||
bool set_default_pib; /**< Set the default PIB. */
|
||||
} mlme_reset_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-RESET confirm callback
|
||||
*
|
||||
* @details The MLME-RESET.confirm primitive is generated by the MLME and
|
||||
* issued to its next higher layer in response to an MLME-RESET.request primitive and
|
||||
* following the receipt of the PLME-SET-TRXSTATE.confirm primitive.
|
||||
*
|
||||
* @param reset status (@c MAC_SUCCESS only).
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.9.2
|
||||
*/
|
||||
typedef void (* mlme_reset_conf_cb_t)(mlme_reset_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-RESET request
|
||||
*
|
||||
* @details The MLME-RESET.request primitive is generated by the next higher layer and
|
||||
* issued to the MLME to request a reset of the MAC sublayer to its initial conditions.
|
||||
* The MLME-RESET.request primitive is issued prior to the use of the MLME-START.request
|
||||
* or the MLME-ASSOCIATE.request primitives.
|
||||
*
|
||||
* @param[in] req pointer to MCPS-RESET.request structure.
|
||||
* @param[in] conf_cb pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.9.1
|
||||
*/
|
||||
void mlme_reset_req(mlme_reset_req_t * req, mlme_reset_conf_cb_t conf_cb);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_RESET_H_INCLUDED
|
|
@ -0,0 +1,181 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_RX_ENABLE_H_INCLUDED
|
||||
#define MAC_MLME_RX_ENABLE_H_INCLUDED
|
||||
|
||||
#if (CONFIG_RXE_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME RX-Enable module declares the MAC RX-Enable primitives and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_rx_enable MAC MLME RX-Enable API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME RX-Enable API.
|
||||
* @details The MAC RX-Enable module declares MLME RX-Enable primitives and necessary types according to
|
||||
* the MAC specification. More specifically, MLME RX-Enable request aka mlme_rx_enable_req(),
|
||||
* and MLME RX-Enable confirm callback typedef aka mlme_rx_enable_conf_cb_t primitives are
|
||||
* declared. One additional primitive not covered by the standard is declared. This is
|
||||
* mlme_rx_enable() which is synchronous (i.e. does not require confirmation) version of
|
||||
* mlme_rx_enable_req().
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MLME-RX-ENABLE.confirm
|
||||
*
|
||||
* @details The MLME-RX-ENABLE.confirm primitive reports the results of an attempt
|
||||
* to enable or disable the receiver.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.10.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
} mlme_rx_enable_conf_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-RX-ENABLE.request
|
||||
*
|
||||
* @details The MLME-RX-ENABLE.request primitive allows the next higher layer
|
||||
* to request that the receiver is either enabled for a finite period of time or disabled.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.10.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_rx_enable_conf_t confirm;
|
||||
|
||||
/**
|
||||
* @details
|
||||
* TRUE if the requested operation can be deferred until the next superframe
|
||||
* if the requested time has already passed.
|
||||
* FALSE if the requested operation is only to be attempted in the current superframe.
|
||||
*
|
||||
* If the issuing device is the PAN coordinator, the term superframe refers to its own
|
||||
* superframe. Otherwise, the term refers to the superframe of the coordinator through
|
||||
* which the issuing device is associated.
|
||||
*
|
||||
* @note This parameter is ignored for nonbeacon-enabled PANs.
|
||||
*/
|
||||
bool defer_permit;
|
||||
|
||||
/**
|
||||
* @details
|
||||
* The number of symbols measured from the start of the superframe before the receiver is
|
||||
* to be enabled or disabled.
|
||||
* This is a 24-bit value, and the precision of this value shall be a minimum of 20 bits,
|
||||
* with the lowest 4 bits being the least significant.
|
||||
*
|
||||
* If the issuing device is the PAN coordinator, the term superframe refers to its own
|
||||
* superframe. Otherwise, the term refers to the superframe of the coordinator through
|
||||
* which the issuing device is associated.
|
||||
*
|
||||
* @note This parameter is ignored for nonbeacon-enabled PANs.
|
||||
*/
|
||||
uint32_t rx_on_time;
|
||||
|
||||
/**
|
||||
* The number of symbols the receiver is to be enabled for.
|
||||
*
|
||||
* If this parameter is equal to 0x000000, the receiver is to be disabled.
|
||||
*/
|
||||
uint32_t rx_on_duration;
|
||||
} mlme_rx_enable_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Customer's function of confirmation.
|
||||
*
|
||||
* @details The MLME-RX-ENABLE.confirm primitive is generated by the MLME and issued to
|
||||
* its next higher layer in response to an MLME-RX-ENABLE.request primitive.
|
||||
*
|
||||
* @param pointer to a confirmation primitive.
|
||||
*/
|
||||
typedef void (* mlme_rx_enable_conf_cb_t)(mlme_rx_enable_conf_t *);
|
||||
|
||||
/**
|
||||
* @brief MLME-RX-ENABLE.request service
|
||||
*
|
||||
* @details The MLME-RX-ENABLE.request primitive is generated by the next higher layer and
|
||||
* issued to the MLME to enable the receiver for a fixed duration, at a time relative to the
|
||||
* start of the current or next superframe on a beacon-enabled PAN or immediately on a
|
||||
* nonbeacon-enabled PAN. This primitive may also be generated to cancel a previously generated
|
||||
* request to enable the receiver. After request completion, user callback will be issued with
|
||||
* valid data stored in structure mlme_rx_enable_conf_t.
|
||||
*
|
||||
* @note The receiver is enabled or disabled exactly once per primitive request.
|
||||
*
|
||||
* @param[in] req pointer to MLME-RX-ENABLE request structure.
|
||||
* @param[in] conf_cb - pointer to confirm function (user callback).
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.10.1
|
||||
*/
|
||||
void mlme_rx_enable_req(mlme_rx_enable_req_t * req, mlme_rx_enable_conf_cb_t conf_cb);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Enables permission for receiving.
|
||||
*
|
||||
* @details Optional. Not covered by a standard.
|
||||
*
|
||||
* @param[in] req pointer to MLME-RX-ENABLE request structure.
|
||||
*
|
||||
* @return status of operation.
|
||||
*/
|
||||
mac_status_t mlme_rx_enable(mlme_rx_enable_req_t * req);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_RXE_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MLME_RX_ENABLE_H_INCLUDED
|
|
@ -0,0 +1,160 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_SCAN_H_INCLUDED
|
||||
#define MAC_MLME_SCAN_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_mlme_beacon_notify.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Scan module declares the MAC Scan primitives and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_scan MAC MLME Scan API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Scan API.
|
||||
* @details The MAC Scan module declares MLME Scan primitives and necessary types according to
|
||||
* the MAC specification. More specifically, MLME Scan request aka mlme_scan_req(), and MLME
|
||||
* Scan confirm callback typedef aka mlme_scan_conf_cb_t primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief Type of scan. */
|
||||
typedef enum
|
||||
{
|
||||
ED_SCAN = 0, /**< Energy detection scan. */
|
||||
ACTIVE_SCAN, /**< Active scan. */
|
||||
PASSIVE_SCAN, /**< Passive scan. */
|
||||
ORPHAN_SCAN /**< Orphan scan. */
|
||||
} mac_scan_type_t;
|
||||
|
||||
/**
|
||||
* @brief MLME-SCAN.confirm
|
||||
*
|
||||
* @details The MLME-SCAN.confirm reports the result of the channel scan request.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.11.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
mac_scan_type_t scan_type; /**< Scan type. */
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
uint32_t unscanned_channels; /**< Unscanned channels. */
|
||||
uint8_t result_list_size; /**< Result list size. */
|
||||
uint8_t * energy_detect_list; /**< Energy detection list. */
|
||||
mac_pan_descriptor_t * pan_descriptor_list; /**< PAN descriptor list. */
|
||||
} mlme_scan_conf_t;
|
||||
|
||||
/**
|
||||
* @brief MLME-SCAN.request
|
||||
*
|
||||
* @details The MLME-SCAN.request primitive is used to initiate a channel
|
||||
* scan over a given list of channels.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.11.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_scan_conf_t confirm;
|
||||
|
||||
mac_scan_type_t scan_type; /**< Scan type. */
|
||||
uint32_t scan_channels; /**< Scan channels. */
|
||||
uint8_t scan_duration; /**< Scan duration. */
|
||||
|
||||
uint8_t pan_descriptors_buf_size; /**< PAN descriptor buffer size. */
|
||||
mac_pan_descriptor_t * pan_descriptors_buf; /**< PAN descriptor buffer. */
|
||||
|
||||
uint8_t energy_detect_buf_size; /**< Energy detection buffer size. */
|
||||
uint8_t * energy_detect_buf; /**< Energy detection buffer. */
|
||||
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_scan_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief User callback to scan request.
|
||||
*
|
||||
* @details The MLME-SCAN.confirm primitive is generated by the MLME and issued to
|
||||
* its next higher layer when the channel scan initiated with
|
||||
* the MLME-SCAN.request primitive has completed.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.11.2
|
||||
*/
|
||||
typedef void (* mlme_scan_conf_cb_t)(mlme_scan_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-SCAN request
|
||||
*
|
||||
* @details The MLME-SCAN.request primitive is generated by the next higher layer and
|
||||
* issued to its MLME to initiate a channel scan to search for activity within the POS
|
||||
* of the device. This primitive can be used to perform an ED scan to determine channel
|
||||
* usage, an active or passive scan to locate beacon frames containing any PAN identifier,
|
||||
* or an orphan scan to locate a PAN to which the device is currently associated.
|
||||
*
|
||||
* @param[in] req MLME-SCAN request structure.
|
||||
* @param[in] conf_cb pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.11.1
|
||||
*/
|
||||
void mlme_scan_req(mlme_scan_req_t * req, mlme_scan_conf_cb_t conf_cb);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_MLME_SCAN_H_INCLUDED
|
|
@ -0,0 +1,150 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_START_H_INCLUDED
|
||||
#define MAC_MLME_START_H_INCLUDED
|
||||
|
||||
#if (CONFIG_START_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "sys_utils.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Start module declares the MAC Start primitives and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_start MAC MLME Start API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Start API.
|
||||
* @details The MAC Start module declares MLME Start primitives and necessary types according to
|
||||
* the MAC specification. More specifically, MLME Start request aka mlme_start_req(), and MLME
|
||||
* Start confirm callback typedef aka mlme_start_conf_cb_t primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief MLME-Start.confirm
|
||||
*
|
||||
* @details The MLME-Start.confirm primitive reports the results of a request
|
||||
* to start the device.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.14.1.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mac_status_t status; /**< Status of operation. */
|
||||
} mlme_start_conf_t;
|
||||
|
||||
/**
|
||||
* @brief MLME-START.request
|
||||
*
|
||||
* @details The MLME-START.request primitive allows the PAN coordinator
|
||||
* to initiate a new PAN or to start using a new superframe configuration.
|
||||
* This primitive may also be used by a device already associated with an
|
||||
* existing PAN to start using a new superframe configuration.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.14.1.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
/** Confirm to this request. */
|
||||
mlme_start_conf_t confirm;
|
||||
|
||||
uint16_t pan_id; /**< PAN ID. */
|
||||
uint8_t logical_channel; /**< Logical channel. */
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
uint32_t start_time; /**< Start time. */
|
||||
uint8_t beacon_order; /**< Beacon order. */
|
||||
uint8_t superframe_order; /**< Superframe order. */
|
||||
bool pan_coordinator; /**< Is PAN Coordinator? */
|
||||
bool battery_life_extension; /**< Is battery life long? */
|
||||
bool coord_realignment; /**< Is coordinator realignment? */
|
||||
#if (CONFIG_SECURE == 1)
|
||||
/* The security parameters for the coordinator realignment are declared below. */
|
||||
uint8_t coord_realign_security_level; /**< Security level. */
|
||||
uint8_t coord_realign_key_id_mode; /**< Key ID mode. */
|
||||
uint64_t coord_realign_key_source; /**< Key source. */
|
||||
uint8_t coord_realign_key_index; /**< Key index. */
|
||||
|
||||
/* The security parameters for the beacon are declared below. */
|
||||
uint8_t beacon_security_level; /**< Security level. */
|
||||
uint8_t beacon_key_id_mode; /**< Key ID mode. */
|
||||
uint64_t beacon_key_source; /**< Key source. */
|
||||
uint8_t beacon_key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_start_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Callback to the next higher layer.
|
||||
*
|
||||
* @details After request completion, passed callback
|
||||
* will be issued with status provided as a parameter.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.14.2.2
|
||||
*/
|
||||
typedef void (* mlme_start_conf_cb_t)(mlme_start_conf_t *);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-START request.
|
||||
*
|
||||
* @details Generated by the next higher layer and issued to its MLME to
|
||||
* request that a device starts using a new superframe configuration.
|
||||
*
|
||||
* @param[in] req MLME-START request structure.
|
||||
* @param[in] conf_cb pointer to user callback.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.14.1.2
|
||||
*/
|
||||
void mlme_start_req(mlme_start_req_t * req, mlme_start_conf_cb_t conf_cb);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_START_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MLME_START_H_INCLUDED
|
|
@ -0,0 +1,153 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_MLME_SYNC_H_INCLUDED
|
||||
#define MAC_MLME_SYNC_H_INCLUDED
|
||||
|
||||
#if (CONFIG_SYNC_ENABLED == 1)
|
||||
|
||||
#include <stdint.h>
|
||||
#include "mac_common.h"
|
||||
#include "mac_task_scheduler.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Sync module declares the MAC Sync primitives and necessary types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_sync MAC MLME Sync API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Sync API.
|
||||
* @details The MAC Sync module declares MLME Sync and sync loss primitives and necessary types according to
|
||||
* the MAC specification. More specifically, MLME Sync request aka mlme_sync_req(), and MLME
|
||||
* Sync Loss indication aka mlme_sync_loss_ind() primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief Sync Loss reason enumeration. */
|
||||
typedef enum
|
||||
{
|
||||
MAC_SYNC_BEACON_LOST, /**< Beacon lost. */
|
||||
MAC_SYNC_REALIGNMENT, /**< Realignment. */
|
||||
MAC_SYNC_PAN_ID_CONFLICT /**< PAN ID Conflict. */
|
||||
} mlme_sync_loss_reason_t;
|
||||
|
||||
/**
|
||||
* @brief MLME-SYNC-LOSS.indication
|
||||
*
|
||||
* @details On receipt of the MLME-SYNC-LOSS.indication primitive, the next
|
||||
* higher layer is notified of a loss of synchronization.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.15.2
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
mlme_sync_loss_reason_t loss_reason; /**< Loss reason. */
|
||||
uint16_t pan_id; /**< PAN ID. */
|
||||
uint8_t logical_channel; /**< Logical channel. */
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
#if (CONFIG_SECURE == 1)
|
||||
uint8_t security_level; /**< Security level. */
|
||||
uint8_t key_id_mode; /**< Key ID mode. */
|
||||
uint64_t key_source; /**< Key source. */
|
||||
uint8_t key_index; /**< Key index. */
|
||||
#endif
|
||||
} mlme_sync_loss_ind_t;
|
||||
|
||||
|
||||
#if (CONFIG_SYNC_REQ_ENABLED == 1)
|
||||
/**
|
||||
* @brief MLME-SYNC.request
|
||||
*
|
||||
* @details The MLME-SYNC.request primitive is generated by the next higher
|
||||
* layer of a device on a beacon-enabled PAN and issued to its MLME to
|
||||
* synchronize with the coordinator.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.15.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Do not edit this field. */
|
||||
mac_abstract_req_t service;
|
||||
|
||||
uint8_t logical_channel; /**< Logical channel. */
|
||||
#ifdef CONFIG_SUB_GHZ
|
||||
uint8_t channel_page; /**< Channel page. */
|
||||
#endif
|
||||
bool track_beacon; /**< Track beacon? */
|
||||
} mlme_sync_req_t;
|
||||
|
||||
/**
|
||||
* @brief MLME-SYNC-LOSS indication.
|
||||
*
|
||||
* @details Generated by the MLME of a device and issued to its next
|
||||
* higher layer in the event of a loss of synchronization with the
|
||||
* coordinator. It is also generated by the MLME of the PAN coordinator
|
||||
* and issued to its next higher layer in the event of a PAN ID conflict.
|
||||
*
|
||||
* @param[in] ind MLME-SYNC-LOSS indication structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.7.4
|
||||
*/
|
||||
extern void mlme_sync_loss_ind(mlme_sync_loss_ind_t * ind);
|
||||
|
||||
|
||||
/**
|
||||
* @brief MLME-SYNC request.
|
||||
*
|
||||
* @details Generated by the next higher layer of a device on a
|
||||
* beacon-enabled PAN and issued to its MLME to synchronize with
|
||||
* the coordinator.
|
||||
*
|
||||
* @param[in] req MLME_SYNC request structure.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.1.15.1
|
||||
*/
|
||||
void mlme_sync_req(mlme_sync_req_t * req);
|
||||
|
||||
#endif // (CONFIG_SYNC_REQ_ENABLED == 1)
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // (CONFIG_SYNC_ENABLED == 1)
|
||||
|
||||
#endif // MAC_MLME_SYNC_H_INCLUDED
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_PANID_CONFLICT_H_INCLUDED
|
||||
#define MAC_PANID_CONFLICT_H_INCLUDED
|
||||
|
||||
#if (CONFIG_PANID_CONFLICT_ENABLED == 1)
|
||||
|
||||
#include "mac_common.h"
|
||||
|
||||
/** @file
|
||||
* @defgroup mac_pan_id PAN ID Conflict API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module for handling PAN ID conflicts.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief A callback function used to notify Pan ID conflict detection algorithm about
|
||||
* a new beacon frame.
|
||||
*
|
||||
* @param p_beacon - pointer to beacon descriptor struct.
|
||||
*/
|
||||
void mac_panid_conflict_beacon_notify_ind(const mac_beacon_ind_t * p_beacon);
|
||||
|
||||
#if (CONFIG_PANID_CONFLICT_RESOLUTION_ENABLED == 1)
|
||||
/**@brief Callback function which handles end of Pan ID conflict cmd TX,
|
||||
* called by FP
|
||||
* @param[in] status Confirmation status to be raised
|
||||
*/
|
||||
void mac_panid_conflict_cb(mac_status_t status);
|
||||
#endif
|
||||
|
||||
/**@brief Indicates whether the pan id conflict was detected
|
||||
*
|
||||
* @return Result of pan id conflict detection
|
||||
*/
|
||||
bool mac_panid_conflict_detected(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif
|
||||
|
||||
#endif /* MAC_PANID_CONFLICT_H_INCLUDED */
|
|
@ -0,0 +1,318 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_SECURITY_H_INCLUDED
|
||||
#define MAC_SECURITY_H_INCLUDED
|
||||
|
||||
#include "sys_queue.h"
|
||||
#include "sec_aes_ccm.h"
|
||||
|
||||
/** @file
|
||||
* The MAC MLME Security module declares the MAC Security types
|
||||
* according to the MAC specification.
|
||||
*
|
||||
* @defgroup mac_security MAC MLME Security API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC MLME Security API.
|
||||
* @details The MAC Security module declares types/macros needed to implement and use the MAC security
|
||||
* engine according to the MAC specification. No routines or callbacks are declared here.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief MAC sublayer security levels.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.6.2.2.1
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MAC_SEC_OFF = 0, /**< Security is OFF. */
|
||||
MAC_SEC_MIC32, /**< MIC32 security. */
|
||||
MAC_SEC_MIC64, /**< MIC64 security. */
|
||||
MAC_SEC_MIC128, /**< MIC128 security. */
|
||||
MAC_SEC_ENC, /**< ENC security. */
|
||||
MAC_SEC_ENC_MIC32, /**< ENC/MIC32 security. */
|
||||
MAC_SEC_ENC_MIC64, /**< ENC/MIC64 security. */
|
||||
MAC_SEC_ENC_MIC128 /**< ENC/MIC128 security. */
|
||||
} mac_security_level_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief MAC key identifier mode.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 7.6.2.2.2
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
MAC_KEY_ID_IMPL = 0, /**< Impl. */
|
||||
MAC_KEY_ID_ONE_OCTET, /**< One octet. */
|
||||
MAC_KEY_ID_FOUR_OCTET, /**< 4 octets. */
|
||||
MAC_KEY_ID_EIGHT_OCTET /**< 8 octets. */
|
||||
} mac_key_id_mode_t;
|
||||
|
||||
/**@brief Size (in bytes) of short security look up item. This size is
|
||||
* set when lookup size equals to 0.
|
||||
*/
|
||||
#define MAC_LOOKUP_DATA_SIZE_SHORT 5
|
||||
|
||||
/**@brief Size (in bytes) of long security Key look up item. This size is
|
||||
* set when lookup size equals to 1.
|
||||
*/
|
||||
#define MAC_KEY_LOOKUP_DATA_SIZE_LONG 9
|
||||
|
||||
/**@brief Size (in bytes) of long security Data look up item. This size is
|
||||
* set when lookup size equals to 1.
|
||||
*/
|
||||
#define MAC_DATA_LOOKUP_DATA_SIZE_LONG 8
|
||||
|
||||
/**@brief Length of \a mac_key_source_t. Equals to extended address length. */
|
||||
#define MAC_KEY_SOURCE_SIZE 8
|
||||
|
||||
/**@brief This bit-mask is used to get UniqueDevice field value of
|
||||
* \a mac_key_device_descr_t.
|
||||
*/
|
||||
#define MAC_KEY_DEVICE_FLAG_UNIQUE 0x01
|
||||
|
||||
/**@brief This bit-mask is used to get BlackListed field value of
|
||||
* \a mac_key_device_descr_t.
|
||||
*/
|
||||
#define MAC_KEY_DEVICE_FLAG_BLACKLISTED 0x02
|
||||
|
||||
/**@brief Length of key. */
|
||||
#define MAC_SECURITY_KEY_SIZE 16
|
||||
|
||||
/**@brief Length of nonce for aes-ccm algorithm .*/
|
||||
#define MAC_SECURITY_NONCE_SIZE 13
|
||||
|
||||
/**@brief Maximum MIC size .*/
|
||||
#define MAX_MIC_SIZE 16
|
||||
|
||||
/**@brief This type is used to store security key .*/
|
||||
typedef uint8_t mac_key_t[MAC_SECURITY_KEY_SIZE];
|
||||
|
||||
/**@brief This type is used to store security key lookup data .*/
|
||||
typedef uint8_t mac_key_lookup_data_t[MAC_KEY_LOOKUP_DATA_SIZE_LONG];
|
||||
|
||||
/**@brief This type is used to store security data lookup data .*/
|
||||
typedef uint8_t mac_data_lookup_data_t[MAC_DATA_LOOKUP_DATA_SIZE_LONG];
|
||||
|
||||
/**@brief This type is used to store security key source address .*/
|
||||
typedef uint64_t mac_key_source_t;
|
||||
|
||||
/**@brief This type represents key LookupDataSize according to Table 94 .*/
|
||||
typedef enum
|
||||
{
|
||||
KEY_LOOKUP_SIZE_FIVE = 0, /**< Size is 5. */
|
||||
KEY_LOOKUP_SIZE_NINE = 1 /**< Size is 9. */
|
||||
} mac_key_lookup_size_t;
|
||||
|
||||
/**@brief This type represents real size of key LookupData .*/
|
||||
typedef enum
|
||||
{
|
||||
KEY_LOOKUP_SIZE_FIVE_VAL = 5, /**< Size is 5. */
|
||||
KEY_LOOKUP_SIZE_NINE_VAL = 9 /**< Size is 9. */
|
||||
} mac_key_lookup_size_val_t;
|
||||
|
||||
/**@brief This type represents data LookupDataSize .*/
|
||||
typedef enum
|
||||
{
|
||||
DATA_LOOKUP_SIZE_FOUR_VAL = 4, /**< Size is 4. */
|
||||
DATA_LOOKUP_SIZE_EIGHT_VAL = 8 /**< Size is 8. */
|
||||
} mac_data_lookup_size_val_t;
|
||||
|
||||
/**@brief Abstract type to work with growing tables such as some of MAC
|
||||
* security attributes.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
sys_queue_t queue; /**< Service field .*/
|
||||
uint8_t size; /**< Number of currently allocated
|
||||
items inside the table .*/
|
||||
} mac_table_t;
|
||||
|
||||
/**@brief Due to processing algorithm this field MUST be the first inside a
|
||||
* table or list.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
sys_queue_item_t item; /**< Service field .*/
|
||||
uint8_t idx; /**< Index inside table .*/
|
||||
} mac_table_item_t;
|
||||
|
||||
/**@brief KeyIdLookupDescriptor as described in Table 94 .*/
|
||||
typedef struct
|
||||
{
|
||||
mac_table_item_t table_service; /**< Service field .*/
|
||||
mac_key_lookup_data_t data; /**< Set of 5 or 9 bytes.
|
||||
Data used to identify the key .*/
|
||||
mac_key_lookup_size_t size; /**< A value of LOOKUP_SIZE_FIVE indicates a set
|
||||
of 5 bytes; a value of LOOKUP_SIZE_NINE
|
||||
indicates a set of 9 bytes .*/
|
||||
} mac_key_id_lookup_descr_t;
|
||||
|
||||
|
||||
/**@brief KeyIdLookupLis as described in Table 89 .*/
|
||||
typedef mac_table_t mac_key_id_lookup_list_t;
|
||||
|
||||
|
||||
/**@brief DeviceDescriptor as described in Table 93 .*/
|
||||
typedef struct
|
||||
{
|
||||
mac_table_item_t table_service; /**< Service field .*/
|
||||
uint16_t pan_id; /**< The 16-bit PAN identifier of the device in
|
||||
this DeviceDescriptor .*/
|
||||
uint16_t short_address; /**< The 16-bit short address of the device in
|
||||
this DeviceDescriptor. A value of
|
||||
#MAC_EXTENDED_ADDRESS_ONLY
|
||||
indicates that this device is using only its
|
||||
extended address. A value of
|
||||
#MAC_BROADCAST_SHORT_ADDRESS
|
||||
indicates that this value is unknown .*/
|
||||
uint64_t extended_address; /**< The 64-bit IEEE extended address of the
|
||||
device in this DeviceDescriptor. This
|
||||
element is also used in unsecuring
|
||||
operations on incoming frames .*/
|
||||
uint32_t frame_counter; /**< The incoming frame counter of the device
|
||||
in this DeviceDescriptor. This value is used
|
||||
to ensure sequential freshness of frames .*/
|
||||
bool exempt; /**< Indication of whether the device may
|
||||
override the minimum security level
|
||||
settings defined in \a mac_security_level_table_t .*/
|
||||
} mac_device_descr_t;
|
||||
|
||||
|
||||
/**@brief DeviceTable as described in Table 93 .*/
|
||||
typedef mac_table_t mac_device_table_t;
|
||||
|
||||
|
||||
/**@brief KeyDeviceDescriptor as described in Table 91 .*/
|
||||
typedef struct
|
||||
{
|
||||
mac_table_item_t table_service; /**< Service field .*/
|
||||
uint8_t device_handle; /**< Handle to the DeviceDescriptor
|
||||
corresponding to the device (see
|
||||
\a mac_device_descr_t).
|
||||
The value is an index of the device descriptor
|
||||
instance from device table .*/
|
||||
uint8_t unique_device : 1; /**< Indication of whether the device indicated
|
||||
by DeviceDescriptorHandle is uniquely
|
||||
associated with the KeyDescriptor, i.e., it
|
||||
is a link key as opposed to a group key .*/
|
||||
uint8_t blacklisted : 1; /**< Indication of whether the device indicated
|
||||
by DeviceDescriptorHandle previously
|
||||
communicated with this key prior to the
|
||||
exhaustion of the frame counter. If TRUE,
|
||||
this indicates that the device shall not use
|
||||
this key further because it exhausted its
|
||||
use of the frame counter used with this
|
||||
key .*/
|
||||
} mac_key_device_descr_t;
|
||||
|
||||
|
||||
/**@brief KeyDeviceList as described in Table 89 .*/
|
||||
typedef mac_table_t mac_key_device_list_t;
|
||||
|
||||
|
||||
/**@brief KeyUsageDescriptor as described in Table 90 .*/
|
||||
typedef struct
|
||||
{
|
||||
mac_table_item_t table_service; /**< Service field .*/
|
||||
|
||||
uint8_t frame_type : 3; /**< See \a mac_frame_type_t .*/
|
||||
uint8_t cmd_frame_id : 4; /**< See \a mac_command_id_t .*/
|
||||
} mac_key_usage_descr_t;
|
||||
|
||||
|
||||
/**@brief KeyUsageList as described in Table 89 .*/
|
||||
typedef mac_table_t mac_key_usage_list_t;
|
||||
|
||||
|
||||
/**@brief KeyDescriptor as described in Table 89 .*/
|
||||
typedef struct
|
||||
{
|
||||
mac_table_item_t table_service; /**< Service field .*/
|
||||
mac_key_id_lookup_list_t id_lookup_list; /**< A list of KeyIdLookupDescriptor entries
|
||||
used to identify this KeyDescriptor .*/
|
||||
mac_key_device_list_t key_device_list; /**< A list of KeyDeviceDescriptor entries
|
||||
indicating which devices are currently
|
||||
using this key, including their blacklist
|
||||
status .*/
|
||||
mac_key_usage_list_t key_usage_list; /**< A list of KeyUsageDescriptor entries
|
||||
indicating which frame types this key may
|
||||
be used with .*/
|
||||
mac_key_t key; /**< The actual value of the key .*/
|
||||
} mac_key_descr_t;
|
||||
|
||||
|
||||
/**@brief KeyTable as described in Table 88 .*/
|
||||
typedef mac_table_t mac_key_table_t;
|
||||
|
||||
|
||||
/**@brief SecurityLevelDescriptor as described in Table 93 .*/
|
||||
typedef struct
|
||||
{
|
||||
mac_table_item_t table_service; /**< Service field. */
|
||||
|
||||
uint16_t frame_type : 3; /**< See \a mac_frame_type_t .*/
|
||||
uint16_t cmd_frame_id : 4; /**< See \a mac_command_id_t .*/
|
||||
uint16_t security_min : 3; /**< The minimal required/expected security
|
||||
level for incoming MAC frames with the
|
||||
indicated frame type and, if present,
|
||||
command frame type (see
|
||||
\a mac_security_level_t) .*/
|
||||
uint16_t override_min : 1; /**< Indication of whether originating devices
|
||||
for which the Exempt flag is set may
|
||||
override the minimum security level
|
||||
indicated by the SecurityMinimum
|
||||
element. If TRUE, this indicates that for
|
||||
originating devices with Exempt status,
|
||||
the incoming security level zero is
|
||||
acceptable, in addition to the incoming
|
||||
security levels meeting the minimum
|
||||
expected security level indicated by the
|
||||
SecurityMinimum element .*/
|
||||
} mac_security_level_descr_t;
|
||||
|
||||
typedef mac_table_t mac_security_level_table_t;
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_SECURITY_H_INCLUDED
|
|
@ -0,0 +1,205 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_TASK_SCHEDULER_H_INCLUDED
|
||||
#define MAC_TASK_SCHEDULER_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "sys_queue.h"
|
||||
#include "sys_time.h"
|
||||
|
||||
/** @file
|
||||
*
|
||||
* @defgroup mac_task_scheduler MAC task scheduler
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module for MAC task scheduling.
|
||||
*/
|
||||
|
||||
/**@brief Identifiers for external requests.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
#if (CONFIG_PURGE_ENABLED == 1)
|
||||
MAC_PURGE_REQ_ID,
|
||||
#endif
|
||||
#if (CONFIG_ASSOCIATE_REQ_ENABLED == 1)
|
||||
MAC_ASSOCIATE_REQ_ID,
|
||||
#endif
|
||||
#if (CONFIG_DISASSOCIATE_ENABLED == 1)
|
||||
MAC_DISASSOCIATE_REQ_ID,
|
||||
#endif
|
||||
MAC_GET_REQ_ID,
|
||||
#if (CONFIG_GTS_ENABLED == 1)
|
||||
MAC_GTS_REQ_ID,
|
||||
#endif
|
||||
MAC_RESET_REQ_ID,
|
||||
#if (CONFIG_RXE_ENABLED == 1)
|
||||
MAC_RX_ENABLE_REQ_ID,
|
||||
#endif
|
||||
MAC_SCAN_REQ_ID,
|
||||
MAC_SET_REQ_ID,
|
||||
#if (CONFIG_SYNC_REQ_ENABLED == 1)
|
||||
MAC_SYNC_REQ_ID,
|
||||
#endif
|
||||
MAC_POLL_REQ_ID,
|
||||
#if (CONFIG_START_ENABLED == 1)
|
||||
MAC_START_REQ_ID,
|
||||
#endif
|
||||
MAC_DATA_REQ_ID,
|
||||
#if (CONFIG_ORPHAN_ENABLED == 1)
|
||||
MAC_ORPHAN_RESP_ID,
|
||||
#endif
|
||||
MAC_REQS_AMOUNT
|
||||
} mac_req_id_t;
|
||||
|
||||
|
||||
/**@brief Identifiers for internal handlers.
|
||||
*
|
||||
* These handlers are used for private MAC task scheduling.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
#if (CONFIG_FFD_DEVICE == 1) && (CONFIG_BEACON_ENABLED == 1)
|
||||
MAC_SUPERFRAME_OUT_TASK_ID,
|
||||
#endif
|
||||
MAC_CSMA_CA_TASK_ID,
|
||||
#if (CONFIG_START_ENABLED == 1)
|
||||
MAC_START_TASK_ID,
|
||||
#endif
|
||||
MAC_FP_TX_TASK_ID,
|
||||
MAC_DATA_DIR_CONF_ID,
|
||||
#if (CONFIG_INDIRECT_ENGINE_ENABLED == 1)
|
||||
MAC_INDIR_ENGINE_REQ_ID,
|
||||
#endif
|
||||
MAC_FP_RX_TASK_ID,
|
||||
#if (CONFIG_ORPHAN_ENABLED == 1)
|
||||
MAC_ORPHAN_IND_ID,
|
||||
#endif
|
||||
#if (CONFIG_DISASSOCIATE_ENABLED == 1)
|
||||
MAC_DISASSOC_IND_ID,
|
||||
#endif
|
||||
#if (CONFIG_SYNC_ENABLED == 1)
|
||||
MAC_SYNC_LOSS_IND_ID,
|
||||
#endif
|
||||
MAC_GET_CONF_ID,
|
||||
MAC_SET_CONF_ID,
|
||||
MAC_REQ_QUEUE_TASK_ID,
|
||||
MAC_POLL_TASK_ID,
|
||||
MAC_SCAN_CONF_ID,
|
||||
MAC_MEM_ALLOCATOR_TASK_ID,
|
||||
MAC_TASKS_AMOUNT
|
||||
} mac_task_id_t;
|
||||
|
||||
|
||||
/**@brief MAC request descriptor.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
sys_queue_item_t item;
|
||||
mac_req_id_t id;
|
||||
void * p_conf_cb; //pointer to confirmation primitive
|
||||
} mac_abstract_req_t;
|
||||
|
||||
/**@brief scheduler memory.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
sys_queue_t outer_req_queue;
|
||||
volatile uint32_t pending_tasks;
|
||||
bool mac_scheduler_busy;
|
||||
} mac_scheduler_mem_t;
|
||||
|
||||
/**@brief MAC task handler prototype.
|
||||
*
|
||||
* @details Handler which will be called by the MAC scheduler.
|
||||
*/
|
||||
typedef void (* mac_task_handler_t)(void);
|
||||
|
||||
/**@brief MAC external requests queue task handler prototype.
|
||||
*
|
||||
* @details Handler which will be called by the MAC scheduler inside
|
||||
* corresponding task handler.
|
||||
*/
|
||||
typedef void (* mac_req_handler_t)(mac_abstract_req_t *);
|
||||
|
||||
/**@brief Initialize MAC scheduler.
|
||||
*
|
||||
* @details Clean up MAC request's queue.
|
||||
*/
|
||||
void mac_init(void);
|
||||
|
||||
/**@brief MAC task handler.
|
||||
*
|
||||
* @details Handler invokes a MAC primitives routine for a request according to
|
||||
* the requests identification.
|
||||
*/
|
||||
void mac_task_handler(void);
|
||||
|
||||
/**@brief Scheduler request from some MAC primitive.
|
||||
*
|
||||
* @details Place request to MAC scheduler queue for a further handling.
|
||||
*
|
||||
* @param[in] p_req Pointer to a request structure.
|
||||
*/
|
||||
void mac_request_schedule(mac_abstract_req_t * p_req);
|
||||
|
||||
/**@brief Internal function of MAC API.
|
||||
*
|
||||
* This function is used to post tasks between MAC primitives.
|
||||
*
|
||||
* @param[in] id MAC task ID.
|
||||
*
|
||||
*/
|
||||
void mac_internal_task_post(mac_task_id_t id);
|
||||
|
||||
/**@brief Internal function of MAC API.
|
||||
*
|
||||
* Notifies mac scheduler that incoming request has been completely
|
||||
* served and may be safely removed from MAC task queue.
|
||||
*
|
||||
* @param[in] p_req Pointer to a request structure.
|
||||
*/
|
||||
void mac_close_request(mac_abstract_req_t * p_req);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_TASK_SCHEDULER_H_INCLUDED
|
|
@ -0,0 +1,151 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 MAC_TIME_H_INCLUDED
|
||||
#define MAC_TIME_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "sys_time.h"
|
||||
#include "hal_timer.h"
|
||||
#include "hal_timer_critical.h"
|
||||
#include "sys_debug.h"
|
||||
|
||||
/** @file
|
||||
* The MAC Time module declares some useful macros/types and routines that deal with the MAC
|
||||
* timer.
|
||||
*
|
||||
* @defgroup mac_time MAC Time API
|
||||
* @ingroup mac_15_4
|
||||
* @{
|
||||
* @brief Module to declare MAC Time API.
|
||||
* @details The MAC Time module declares some useful macros/types and routines that deal with the MAC
|
||||
* timer. More specifically, some convertion routines such as mac_timestamp_from_systime(),
|
||||
* mac_time_from_us(), and mac_time_to_us() are declared here.
|
||||
*/
|
||||
|
||||
/**@brief This mask shall always be used after any mathematical operation on
|
||||
* mac_time_t to avoid overflow.
|
||||
*/
|
||||
#define MAC_TIME_MASK 0xFFFFFFULL
|
||||
|
||||
/**@brief Type of MAC time in symbols. */
|
||||
typedef uint32_t mac_time_t;
|
||||
|
||||
/**@brief Type is used to save timestamps with microsecond precision. */
|
||||
typedef uint32_t mac_timestamp_t;
|
||||
|
||||
|
||||
/**@brief Gets timestamp from system time.
|
||||
*
|
||||
* @param[in] time_us System time.
|
||||
*
|
||||
* @return Time in us but smaller type size.
|
||||
*/
|
||||
static inline mac_timestamp_t mac_timestamp_from_systime(sys_time_t time_us)
|
||||
{
|
||||
return (mac_timestamp_t)time_us;
|
||||
}
|
||||
|
||||
/**@brief Converts microseconds to symbol time.
|
||||
*
|
||||
* @details Symbol time is measured in PHY Symbol Periods (16 us).
|
||||
*
|
||||
* @param[in] time_us Time in microseconds.
|
||||
*
|
||||
* @return Time in PHY Symbol Periods (16 us).
|
||||
*/
|
||||
static inline mac_time_t mac_time_from_us(sys_time_t time_us)
|
||||
{
|
||||
return (mac_time_t)((time_us >> 4ull) & MAC_TIME_MASK);
|
||||
}
|
||||
|
||||
|
||||
/**@brief Converts symbol time to microseconds.
|
||||
*
|
||||
* @details Symbol time is measured in PHY Symbol Periods (16 us).
|
||||
*
|
||||
* @param[in] time_symbol Time in PHY Symbol Periods (16 us).
|
||||
*
|
||||
* @return Time in microseconds.
|
||||
*/
|
||||
static inline sys_time_t mac_time_to_us(mac_time_t time_symbol)
|
||||
{
|
||||
return time_symbol << 4u;
|
||||
}
|
||||
|
||||
|
||||
/**@brief Starts the critical MAC timer.
|
||||
*
|
||||
* @details The callback function of the critical MAC timer will be called from
|
||||
* the timer's interrupt routine. Only one critical MAC timer can run
|
||||
* at the same time.
|
||||
*
|
||||
* @warning This is internal MAC functionality, needed for the realtime channel access.
|
||||
* This function must not be used by other modules.
|
||||
*
|
||||
* @param[in] interval_us Interval in microseconds, after which the callback
|
||||
* function will be called.
|
||||
* @param[in] callback Callback function to be called after the specified inteval.
|
||||
*/
|
||||
static inline void mac_timer_critical_start(sys_time_t interval_us, void (* callback)(void))
|
||||
{
|
||||
// Make sure interval_us fits into 32 bits, since hardware critical timer is 32 bit.
|
||||
ASSERT(interval_us < (1ULL << 32));
|
||||
|
||||
hal_timer_critical_start((uint32_t)interval_us, callback);
|
||||
}
|
||||
|
||||
|
||||
/**@brief Stops the critical MAC timer.
|
||||
*
|
||||
* @details After critical MAC timer is stopped with this function, its callback will not be called.
|
||||
*
|
||||
* @warning This is internal MAC functionality, needed for the realtime channel access.
|
||||
* This function must not be used by other modules.
|
||||
*/
|
||||
static inline void mac_timer_critical_stop(void)
|
||||
{
|
||||
hal_timer_critical_stop();
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // MAC_TIME_H_INCLUDED
|
|
@ -0,0 +1,240 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 PHY_COMMON_H_INCLUDED
|
||||
#define PHY_COMMON_H_INCLUDED
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of commonly used PHY routines and necessary macros/types.
|
||||
*
|
||||
* @defgroup phy_common PHY Common API
|
||||
* @ingroup phy_15_4
|
||||
* @{
|
||||
* @brief Module to declare Common PHY API
|
||||
* @details The Common PHY module contains declarations of commonly used PHY routines and necessary macros/types.
|
||||
*/
|
||||
|
||||
/**@brief The maximum PSDU size (in octets) the PHY shall be able to receive (aMaxPHYPacketSize).
|
||||
*
|
||||
* @details See Table 22 - PHY constants.
|
||||
*/
|
||||
#define PHY_MAX_PACKET_SIZE 127
|
||||
|
||||
|
||||
/**@brief The maximum PHR size (in octets).
|
||||
*
|
||||
* @details See 6.3 PPDU format.
|
||||
*/
|
||||
#define PHY_MAX_HEADER_SIZE 1
|
||||
|
||||
/**@brief Maximum PPDU size */
|
||||
#define PHY_MAX_PPDU_SIZE (PHY_MAX_HEADER_SIZE + PHY_MAX_PACKET_SIZE)
|
||||
|
||||
/**@brief Position of PHY header related to income PPDU start pointer.*/
|
||||
#define PHY_HEADER_POS (-1)
|
||||
|
||||
/**@brief Size of PHY header in bytes.*/
|
||||
#define PHY_HEADER_SIZE 1
|
||||
|
||||
/**@brief Maximum channel number.*/
|
||||
#define PHY_MAX_CHANNEL_NUM 0x1Au
|
||||
|
||||
/**@brief Minimum channel number.*/
|
||||
#define PHY_MIN_CHANNEL_NUM 0x0Bu
|
||||
|
||||
// for 2400 MHz O-QPSK 1 octet = 2 symbols 1 symbol = 32bits chip
|
||||
#define aMaxPHYPacketSize PHY_MAX_PACKET_SIZE // in octets
|
||||
#define aTurnaroundTime 12 // in symbols
|
||||
|
||||
#define aTurnaroundTimeUs 192 // in us
|
||||
|
||||
|
||||
// Read only parameters
|
||||
#define PHY_CURRENT_PAGE 0x0u
|
||||
#define PHY_CHANNEL_SUPPORTED 0x07FFF800ul
|
||||
#define PHY_SHR_DURATION 10u
|
||||
#define PHY_MAX_FRAME_DURATION (PHY_SHR_DURATION + (int)((aMaxPHYPacketSize + 1) * PHY_SYMBOLS_PER_OCTET))
|
||||
#define PHY_SYMBOLS_PER_OCTET 2u
|
||||
|
||||
// CCA values
|
||||
#define PHY_TRX_CCA_MODE0 0
|
||||
#define PHY_TRX_CCA_MODE1 1
|
||||
#define PHY_TRX_CCA_MODE2 2
|
||||
#define PHY_TRX_CCA_MODE3 3
|
||||
|
||||
|
||||
/** @brief Minimum value that can be used to set radio transmit power. Equals
|
||||
* to -32 dBm.
|
||||
*
|
||||
* This is a combination of digits which includes:
|
||||
* 2 MSBs represent the tolerance on the transmit power
|
||||
* 6 LSBs which may be written to, represent a signed integer in twos-complement format,
|
||||
* corresponding to the nominal transmit power of the device in decibels relative to 1 mW.
|
||||
* All combinations less than 0xBF are valid.
|
||||
*/
|
||||
#define PHY_MIN_TX_POWER 0x20
|
||||
|
||||
/** @brief Internal parameter of the PHY layer.
|
||||
*
|
||||
* @details Position of the sign bit inside transmit power attribute.*/
|
||||
#define PHY_TRANSMIT_POWER_SIGN_BIT_POS 5
|
||||
|
||||
/** @brief Internal parameter of the PHY layer.
|
||||
*
|
||||
* @details This mask hides transmit power from transmit power attribute value,
|
||||
* but leaves precision bitfield.
|
||||
*/
|
||||
#define PHY_TRANSMIT_POWER_MASK 0xC0
|
||||
|
||||
/** @brief Internal parameter of the PHY layer.
|
||||
*
|
||||
* @details This mask hides precision bitfield from transmit power attribute value,
|
||||
* leaving transmit power unchanged.
|
||||
*/
|
||||
#define PHY_TRANSMIT_POWER_MASK_INV 0x3F
|
||||
|
||||
// Possible transmit power
|
||||
#define DBM_11 ( 11 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_10 ( 10 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_9 ( 9 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_8 ( 8 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_7 ( 7 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_6 ( 6 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_5 ( 5 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_4 ( 4 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_3 ( 3 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_2 ( 2 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_1 ( 1 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_0 ( 0 & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_1 (( -1) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_2 (( -2) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_3 (( -3) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_4 (( -4) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_5 (( -5) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_6 (( -6) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_7 (( -7) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_8 (( -8) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_9 (( -9) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_10 ((-10) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_11 ((-11) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_12 ((-12) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_13 ((-13) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_14 ((-14) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_15 ((-15) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_16 ((-16) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_17 ((-17) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_18 ((-18) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_19 ((-19) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_20 ((-20) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_21 ((-21) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_22 ((-22) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_23 ((-23) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_24 ((-24) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_25 ((-25) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_26 ((-26) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
#define DBM_MIN_27 ((-27) & PHY_TRANSMIT_POWER_MASK_INV)
|
||||
|
||||
|
||||
/**@brief Common PHY enumerations description used in various PHY primitives.
|
||||
*
|
||||
* @details See Table 18-PHY enumerations description for detailed info on the statuses up to PHY_READ_ONLY.
|
||||
* The statuses with higher numbers are implementation specific and used for synchronous API only.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
/** The CCA attempt has detected a busy channel. */
|
||||
PHY_BUSY = 0x00,
|
||||
|
||||
/** The transceiver is asked to change its state while receiving. */
|
||||
PHY_BUSY_RX = 0x01,
|
||||
|
||||
/** The transceiver is asked to change its state while transmitting. */
|
||||
PHY_BUSY_TX = 0x02,
|
||||
|
||||
/** The transceiver is to be switched off immediately. */
|
||||
PHY_FORCE_TRX_OFF = 0x03,
|
||||
|
||||
/** The CCA attempt has detected an idle channel. */
|
||||
PHY_IDLE = 0x04,
|
||||
|
||||
/** A SET/GET request was issued with a parameter in the primitive that is
|
||||
out of the valid range. */
|
||||
PHY_INVALID_PARAMETER = 0x05,
|
||||
|
||||
/** The transceiver is in or is to be configured into the receiver enabled state. */
|
||||
PHY_RX_ON = 0x06,
|
||||
|
||||
/** A SET/GET, an ED operation, or a transceiver state change was successful. */
|
||||
PHY_SUCCESS = 0x07,
|
||||
|
||||
/** The transceiver is in or is to be configured into the transceiver disabled state. */
|
||||
PHY_TRX_OFF = 0x08,
|
||||
|
||||
/** The transceiver is in or is to be configured into the transmitter enabled state. */
|
||||
PHY_TX_ON = 0x09,
|
||||
|
||||
/** A SET/GET request was issued with the identifier of an attribute that is not supported. */
|
||||
PHY_UNSUPPORTED_ATTRIBUTE = 0x0A,
|
||||
|
||||
/** A SET/GET request was issued with the identifier of an attribute that is read-only.*/
|
||||
PHY_READ_ONLY = 0x0B,
|
||||
|
||||
|
||||
/* Statuses out of the standard. They are used for synchronous API */
|
||||
/** Transceiver is forced to change it's state to PHY_TX_ON (potential packet drop). */
|
||||
PHY_FORCE_TX_ON = 0xFC,
|
||||
|
||||
/** Data cannot be sent due to failed CCA results.*/
|
||||
PHY_CHANNEL_ACCESS_FAILURE = 0xFD,
|
||||
|
||||
/** Data had been sent but ACK frame hasn't been received.*/
|
||||
PHY_NO_ACK = 0xFE,
|
||||
|
||||
/** PHY is not available for synchronous access */
|
||||
PHY_IS_NOT_AVAILABLE = 0xFF
|
||||
} phy_enum_t;
|
||||
|
||||
/**@brief PHY status type.*/
|
||||
typedef phy_enum_t phy_status_t;
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // PHY_COMMON_H_INCLUDED
|
|
@ -0,0 +1,187 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 PHY_PD_DATA_H_INCLUDED
|
||||
#define PHY_PD_DATA_H_INCLUDED
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "sys_utils.h"
|
||||
#include "sys_time.h"
|
||||
#include "phy_common.h"
|
||||
#include "mac_time.h"
|
||||
#include "sys_queue.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of PHY Data transmission routines and necessary types.
|
||||
*
|
||||
* @defgroup phy_data PHY Data API
|
||||
* @ingroup phy_15_4
|
||||
* @{
|
||||
* @brief Module to declare PHY Data API
|
||||
* @details The PHY Data module declares the PHY Data transmission routines and necessary types according to
|
||||
* the PHY specification. More specifically, PHY data request pd_data_req(), PHY data confirm
|
||||
* pd_data_conf(), and PHY Data indication pd_data_ind() primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief PD-DATA.request parameters.
|
||||
*
|
||||
* @details See 6.2.1.1 PD-DATA.request.
|
||||
* See Table 6 - PD-DATA.request parameters.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** The set of octets forming the PSDU to be transmitted by the PHY entity. */
|
||||
uint8_t * psdu;
|
||||
|
||||
/** The number of octets contained in the PSDU to be transmitted by the PHY entity.
|
||||
Valid range: less or equal to @ref PHY_MAX_PACKET_SIZE. */
|
||||
uint8_t psdu_length;
|
||||
} pd_data_req_t;
|
||||
|
||||
/**@brief Private information which is passed with PD-DATA.confirm.
|
||||
* Not covered by standard.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** pending value to store pending bit value if frame was acknowledged. */
|
||||
bool pending;
|
||||
} pd_data_conf_private_t;
|
||||
|
||||
/**@brief PD-DATA.confirm parameters.
|
||||
*
|
||||
* @details See 6.2.1.2 PD-DATA.confirm.
|
||||
* See Table 7 - PD-DATA.confirm parameters.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Service field. */
|
||||
pd_data_conf_private_t service;
|
||||
|
||||
/** The result of the request to transmit a packet.
|
||||
* Valid range: PHY_SUCCESS, PHY_RX_ON, PHY_TRX_OFF, PHY_BUSY_TX.
|
||||
* See @ref phy_enum_t.
|
||||
*
|
||||
* When radio chip successfully transmits data, but cannot receive
|
||||
* ACK in FAST_ACK mode, the result is PHY_TX_ON.
|
||||
*/
|
||||
phy_enum_t status;
|
||||
} pd_data_conf_t;
|
||||
|
||||
/**@brief Private information which is passed with PD-DATA.indication.
|
||||
* Not covered by standard.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** RSSI value, which corresponds to packet that caused this indication. */
|
||||
int8_t rssi;
|
||||
|
||||
/** Buffer to store incoming frame. */
|
||||
uint8_t frame_buffer[PHY_MAX_PACKET_SIZE + PHY_MAX_HEADER_SIZE];
|
||||
|
||||
/** Timestamp of the moment when PHY header octet reception has been started. */
|
||||
mac_timestamp_t timestamp;
|
||||
|
||||
/** This field allows storing instances of this structure in a queue. */
|
||||
sys_queue_item_t queue_item;
|
||||
#ifdef CONFIG_PHY_CERT_CRC_HOOK
|
||||
bool crc_status;
|
||||
#endif
|
||||
} pd_data_ind_private_t;
|
||||
|
||||
/**@brief PD-DATA.indication parameters.
|
||||
*
|
||||
* @details See 6.2.1.3 PD-DATA.indication.
|
||||
* See Table 8 - PD-DATA.indication parameters.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Service field. */
|
||||
pd_data_ind_private_t service;
|
||||
|
||||
/** The set of octets forming the PSDU received by the PHY entity. */
|
||||
uint8_t * psdu;
|
||||
|
||||
/** The number of octets contained in the PSDU received by the PHY entity.
|
||||
Valid range: less or equal to @ref PHY_MAX_PACKET_SIZE. */
|
||||
uint8_t psdu_length;
|
||||
|
||||
/** Link quality (LQI) value measured during reception of the PPDU (see 6.9.8).
|
||||
Valid range: 0x00 - 0xFF. */
|
||||
uint8_t ppdu_link_quality;
|
||||
} pd_data_ind_t;
|
||||
|
||||
/**@brief PD-DATA.request primitive.
|
||||
*
|
||||
* @details The PD-DATA.request primitive requests the transfer of an MPDU (i.e., PSDU)
|
||||
* from the MAC sublayer to the local PHY entity.
|
||||
* See 6.2.1.1 PD-DATA.request.
|
||||
*
|
||||
* @param[in] req Pointer to PD-DATA.request parameters. See @ref pd_data_req_t.
|
||||
*/
|
||||
void pd_data_req(pd_data_req_t * req);
|
||||
|
||||
/**@brief PD-DATA.confirm primitive.
|
||||
*
|
||||
* @details Callback function, implemented by the next higher layer,
|
||||
* which handles the PD-DATA.confirm primitive.
|
||||
* See 6.2.1.2 PD-DATA.confirm.
|
||||
*
|
||||
* @param[out] conf Pointer to PD-DATA.confirm parameters. See @ref pd_data_conf_t.
|
||||
*/
|
||||
void pd_data_conf(pd_data_conf_t * conf);
|
||||
|
||||
/**@brief PD-DATA.indication primitive.
|
||||
*
|
||||
* @details The PD-DATA.indication primitive indicates the transfer of an MPDU (i.e., PSDU)
|
||||
* from the PHY to the local MAC sublayer entity.
|
||||
* See 6.2.1.3 PD-DATA.indication.
|
||||
* This function must be implemented by the next higher layer.
|
||||
*
|
||||
* @param[out] ind Pointer to PD-DATA.indication parameters. See @ref pd_data_ind_t.
|
||||
* Data are valid until next fully received packet.
|
||||
*/
|
||||
void pd_data_ind(pd_data_ind_t * ind);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // PHY_PD_DATA_H_INCLUDED
|
|
@ -0,0 +1,106 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 PHY_PLME_CCA_H_INCLUDED
|
||||
#define PHY_PLME_CCA_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "phy_common.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of Clear Channel Assessment PHY routines and necessary types.
|
||||
*
|
||||
* @defgroup phy_cca PHY CCA API
|
||||
* @ingroup phy_15_4
|
||||
* @{
|
||||
* @brief Module to declare PHY Clear Channel Assessment API
|
||||
* @details The PHY CCA module declares Clear Channel Assessment PHY routines and necessary types according to
|
||||
* the PHY specification. More specifically, PHY CCA request plme_cca_req(), PHY CCA confirm
|
||||
* plme_cca_conf() primitives are declared. An additional primitive not covered by the standard is declared.
|
||||
* This is plme_cca() which is a synchronous version of plme_cca_req().
|
||||
*/
|
||||
|
||||
/**@brief PLME-CCA.confirm parameters
|
||||
*
|
||||
* @details The PLME-CCA.confirm primitive is generated by
|
||||
* the initiating PLME and issued to its next higher layer
|
||||
* in response to an PLME-CCA.request primitive.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.2.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** One of PHY_TRX_OFF, PHY_BUSY or PHY_IDLE. */
|
||||
phy_enum_t status;
|
||||
} plme_cca_conf_t;
|
||||
|
||||
|
||||
/**@brief PLME-CCA.request
|
||||
*
|
||||
* @details Request for clear channel assessment.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.1
|
||||
*/
|
||||
void plme_cca_req(void);
|
||||
|
||||
|
||||
/**@brief PLME-CCA.confirm callback function, implemented by the next higher layer.
|
||||
*
|
||||
* @details The PLME-CCA.confirm primitive is generated by the PLME and issued
|
||||
* to its next higher layer in response to an PLME-CCA.request primitive.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.2
|
||||
*
|
||||
* @param[out] conf Pointer to PLME-CCA.confirm parameters
|
||||
*/
|
||||
void plme_cca_conf(plme_cca_conf_t * conf);
|
||||
|
||||
|
||||
/**@brief Direct (synchronous) PLME-CCA.request
|
||||
*
|
||||
* @details Optional. Not covered by a standard.
|
||||
*
|
||||
* @return One of PHY_TRX_OFF, PHY_BUSY or PHY_IDLE,
|
||||
* or implementation defined error code in case of
|
||||
* unavailability of access to system resources.
|
||||
*/
|
||||
phy_enum_t plme_cca(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // PHY_PLME_CCA_H_INCLUDED
|
|
@ -0,0 +1,110 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 PHY_PLME_ED_H_INCLUDED
|
||||
#define PHY_PLME_ED_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "phy_common.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of Energy Detection PHY routines and necessary types.
|
||||
*
|
||||
* @defgroup phy_ed PHY ED API
|
||||
* @ingroup phy_15_4
|
||||
* @{
|
||||
* @brief Module to declare PHY Energy Detection API
|
||||
* @details The PHY ED module declares Energy Detection PHY routines and necessary types according to
|
||||
* the PHY specification. More specifically, PHY ED request plme_ed_req(), PHY ED confirm
|
||||
* plme_ed_conf() primitives are declared.
|
||||
*/
|
||||
|
||||
/**@brief Describes the current state of the ED algorithm. */
|
||||
typedef enum
|
||||
{
|
||||
PHY_PLME_ED_STATE_IDLE, /**< Algorithm is idle. */
|
||||
PHY_PLME_ED_STATE_BUSY /**< Currently performing ED. */
|
||||
} phy_plme_ed_state_t;
|
||||
|
||||
/**@brief This structure holds static data of this module. */
|
||||
typedef struct
|
||||
{
|
||||
phy_plme_ed_state_t state;
|
||||
} phy_plme_ed_mem_t;
|
||||
|
||||
/**@brief PLME-ED.confirm parameters.
|
||||
*
|
||||
* @details The PLME-ED.confirm primitive is generated by the PLME and issued
|
||||
* to its next higher layer in response to an PLME-ED.request primitive.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.4.1.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** One of PHY_SUCCESS, PHY_TRX_OFF or PHY_TX_ON. */
|
||||
phy_enum_t status;
|
||||
|
||||
/** Energy level for the current channel, if status is SUCCESS. */
|
||||
uint8_t energy_level;
|
||||
} plme_ed_conf_t;
|
||||
|
||||
|
||||
/**@brief PLME-ED.request.
|
||||
*
|
||||
* @details Request ED measurement for the current channel.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.3.
|
||||
*/
|
||||
void plme_ed_req(void);
|
||||
|
||||
|
||||
/**@brief The PLME-ED.confirm callback function, implemented by the next higher layer.
|
||||
*
|
||||
* @details The PLME-ED.confirm primitive is generated by the PLME and issued
|
||||
* to its next higher layer in response to an PLME-ED.request primitive.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.4.
|
||||
*
|
||||
* @param[out] conf Pointer to PLME-ED.confirm parameters
|
||||
*/
|
||||
void plme_ed_conf(plme_ed_conf_t * conf);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // PHY_PLME_ED_H_INCLUDED
|
|
@ -0,0 +1,212 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 PHY_PLME_PIB_H_INCLUDED
|
||||
#define PHY_PLME_PIB_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
#include "phy_common.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of PHY Information Base routines and necessary types.
|
||||
*
|
||||
* @defgroup phy_pib PHY PIB API
|
||||
* @ingroup phy_15_4
|
||||
* @{
|
||||
* @brief Module to declare PHY Information Base API
|
||||
* @details The PHY PIB module declares PHY Information Base routines and necessary types according to
|
||||
* the PHY specification. More specifically, PHY PIB Get request plme_get_req(), PHY PIB Set request
|
||||
* plme_set_req(), PHY PIB Get confirm plme_get_conf(), and PHY PIB Set confirm plme_set_conf()
|
||||
* primitives are declared. Two additional primitives not covered by the standard are declared. These are
|
||||
* plme_get() and plme_set() which are synchronous versions of plme_get_req() and plme_set_req() accordingly.
|
||||
*/
|
||||
|
||||
#define PHY_TX_POWER_TOLERANCE_1DB 0x00
|
||||
#define PHY_TX_POWER_TOLERANCE_3DB 0x40
|
||||
#define PHY_TX_POWER_TOLERANCE_6DB 0x80
|
||||
#define PHY_TX_POWER_TOLERANCE_MASK 0xC0
|
||||
|
||||
/**
|
||||
* @brief PHY PIB attribute identificators.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.4.2.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
PHY_CURRENT_CHANNEL_ID = 0x00, /**< Current channel. */
|
||||
PHY_CHANNELS_SUPPORTED_ID = 0x01, /**< Supported channels. @note read only. */
|
||||
PHY_TRANSMIT_POWER_ID = 0x02, /**< Transmit power. */
|
||||
PHY_CCA_MODE_ID = 0x03, /**< CCA mode. */
|
||||
PHY_CURRENT_PAGE_ID = 0x04, /**< Current page. */
|
||||
PHY_MAX_FRAME_DURATION_ID = 0X05, /**< MAX Frame duration. @note read only. */
|
||||
PHY_SHR_DURATION_ID = 0x06, /**< SHR Duration. @note read only. */
|
||||
PHY_SYMBOLS_PER_OCTET_ID = 0x07, /**< Symbols per octet. @note read only. */
|
||||
} plme_pib_attr_id_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief PHY PIB attribute type sizes.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, Table 23.
|
||||
*/
|
||||
typedef union
|
||||
{
|
||||
uint8_t phy_current_channel; /**< Current channel. */
|
||||
uint32_t phy_channels_supported; /**< Supported channels. */
|
||||
int8_t phy_transmit_power; /**< Returns one of the DBM_xxx macro values. */
|
||||
uint8_t phy_cca_mode; /**< CCA mode. */
|
||||
uint8_t phy_current_page; /**< Current page. */
|
||||
uint16_t phy_max_frame_duration; /**< MAX Frame duration. */
|
||||
uint8_t phy_shr_duration; /**< SHR Duration. */
|
||||
uint16_t phy_symbols_per_octet; /**< Symbols per octet. */
|
||||
} phy_pib_item_t;
|
||||
|
||||
|
||||
/**@brief PLME-GET.request parameters.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.5.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
plme_pib_attr_id_t pib_attribute; /**< PIB attribute. */
|
||||
} plme_get_req_t;
|
||||
|
||||
|
||||
/**@brief PLME-GET.confirm parameters.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.6.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
phy_status_t status; /**< Status of operation. */
|
||||
plme_pib_attr_id_t pib_attribute; /**< PIB attribute. */
|
||||
phy_pib_item_t pib_attribute_value; /**< Attribute value. */
|
||||
} plme_get_conf_t;
|
||||
|
||||
|
||||
/**@brief PLME-SET.request parameters.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.9.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
plme_pib_attr_id_t pib_attribute; /**< PIB attribute. */
|
||||
phy_pib_item_t pib_attribute_value; /**< Attribute value. */
|
||||
} plme_set_req_t;
|
||||
|
||||
|
||||
/**@brief PLME-SET.confirm parameters.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.10.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
phy_status_t status; /**< Status of operation. */
|
||||
plme_pib_attr_id_t pib_attribute; /**< PIB attribute. */
|
||||
} plme_set_conf_t;
|
||||
|
||||
|
||||
/**@brief PLME-GET.request.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.5.
|
||||
*
|
||||
* @param[in] req Pointer to PLME-GET.request parameters. See @ref plme_get_req_t.
|
||||
*/
|
||||
void plme_get_req(plme_get_req_t * req);
|
||||
|
||||
|
||||
/**@brief PLME-GET.confirm callback function, implemented by the next higher layer.
|
||||
*
|
||||
* @details The PLME-GET.confirm primitive is generated by the PLME and issued
|
||||
* to its next higher layer in response to an PLME-GET.request primitive.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.6.
|
||||
*
|
||||
* @param[out] conf Pointer to PLME-GET.confirm parameters. See @ref plme_get_conf_t.
|
||||
*/
|
||||
void plme_get_conf(plme_get_conf_t * conf);
|
||||
|
||||
|
||||
/**@brief PLME-SET.request.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.9.
|
||||
*
|
||||
* @param[in] req Pointer to PLME-SET.request parameters. See @ref plme_set_req_t.
|
||||
*/
|
||||
void plme_set_req(plme_set_req_t * req);
|
||||
|
||||
|
||||
/**@brief PLME-SET.confirm callback function, implemented by the next higher layer.
|
||||
*
|
||||
* @details In accordance with IEEE Std 802.15.4-2006, section 6.2.2.10.
|
||||
*
|
||||
* @param[out] conf Pointer to PLME-SET.confirm parameters. See @ref plme_set_conf_t.
|
||||
*/
|
||||
void plme_set_conf(plme_set_conf_t * conf);
|
||||
|
||||
/**
|
||||
* @brief Getting parameters from PIB directly (without request - confirm approach)
|
||||
*
|
||||
* @details Optional. Not covered by a standard.
|
||||
*
|
||||
* @param[in] id attribute id.
|
||||
* @param[out] mem pointer to memory for parameter storing.
|
||||
*
|
||||
* @return status of operation.
|
||||
*/
|
||||
phy_status_t plme_get(plme_pib_attr_id_t id, void * mem);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Setting parameters to PIB directly (without request - confirm approach)
|
||||
*
|
||||
* @details Optional. Not covered by a standard.
|
||||
*
|
||||
* @param[in] id attribute id.
|
||||
* @param[out] mem pointer to memory for parameter storing.
|
||||
*
|
||||
* @return status of operation.
|
||||
*/
|
||||
phy_status_t plme_set(plme_pib_attr_id_t id, void * mem);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // PHY_PLME_PIB_H_INCLUDED
|
|
@ -0,0 +1,135 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 PHY_PLME_TRX_H_INCLUDED
|
||||
#define PHY_PLME_TRX_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "phy_common.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of PHY TRX routines and necessary types.
|
||||
*
|
||||
* @defgroup phy_trx PHY TRX API
|
||||
* @ingroup phy_15_4
|
||||
* @{
|
||||
* @brief Module to declare PHY Transceiver State API
|
||||
* @details The PHY TRX module declares Transceiver state change PHY routines and necessary types according to
|
||||
* the PHY specification. More specifically, PHY set TRX state request plme_set_trx_state_req(),
|
||||
* PHY TRX state change confirm plme_set_trx_state_conf() primitives are declared. An additional
|
||||
* primitive not covered by the standard is declared. This is plme_set_trx_state() which is a synchronous
|
||||
* version of plme_set_trx_state_req().
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief PLME-SET_TRX_STATE.request parameters.
|
||||
*
|
||||
* @details The PLME-SET_TRX_STATE.request primitive is generated
|
||||
* by the next higher layer of a device and issued to its PLME to
|
||||
* set transmitter status.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.7.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** One of PHY_RX_ON, PHY_TRX_OFF, PHY_FORCE_TRX_OFF, PHY_TX_ON or PHY_FORCE_TX_ON. */
|
||||
phy_enum_t state;
|
||||
} plme_trx_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief PLME-TRX.confirm parameters.
|
||||
*
|
||||
* @details The PLME-TRX.confirm primitive is generated by
|
||||
* PLME and issued to its next higher layer in response to
|
||||
* an PLME-SET_TRX_STATE.request primitive.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.8.1
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Holds result of trx state change request.
|
||||
*
|
||||
* @details Equals to PHY_SUCCESS if state changed successfully
|
||||
* or current PHY state in either case.
|
||||
*/
|
||||
phy_enum_t status;
|
||||
} plme_trx_conf_t;
|
||||
|
||||
|
||||
/**@brief PLME-SET_TRX_STATE request.
|
||||
*
|
||||
* @details Request PHY to change internal operating state.
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.7
|
||||
*
|
||||
* @param[in] req Pointer to PLME-SET_TRX_STATE.request parameters.
|
||||
* See @ref plme_trx_req_t.
|
||||
*/
|
||||
void plme_set_trx_state_req(plme_trx_req_t * req);
|
||||
|
||||
|
||||
/**@brief PLME-SET_TRX_STATE.confirm callback function, implemented by the next higher layer.
|
||||
*
|
||||
* @details The PLME-SET_TRX_STATE.confirm primitive is generated
|
||||
* by the PLME and issued to its next higher layer in response to
|
||||
* an PLME-SET_TRX_STATE.request primitive.
|
||||
*
|
||||
* In accordance with IEEE Std 802.15.4-2006, section 6.2.2.8
|
||||
*
|
||||
* @param[out] conf Pointer to PLME-TRX.confirm parameters. See @ref plme_trx_conf_t.
|
||||
*/
|
||||
void plme_set_trx_state_conf(plme_trx_conf_t * conf);
|
||||
|
||||
|
||||
/**@brief Direct (synchronous) PLME-SET_TRX_STATE access.
|
||||
*
|
||||
* @details Optional. Not covered by the standard.
|
||||
|
||||
* @param[in] state One of PHY_RX_ON, PHY_TRX_OFF, PHY_FORCE_TRX_OFF or PHY_TX_ON.
|
||||
*
|
||||
* @return PHY_SUCCESS if state changed successfully or current PHY state
|
||||
* in either case.
|
||||
*/
|
||||
phy_enum_t plme_set_trx_state(phy_enum_t state);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // PHY_PLME_TRX_H_INCLUDED
|
|
@ -0,0 +1,99 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 RAL_API_SPEC_H_INCLUDED
|
||||
#define RAL_API_SPEC_H_INCLUDED
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
/**
|
||||
* @defgroup ral_api_spec RAL Special API
|
||||
* @ingroup ral_api
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**@brief Specific CCA MODE for FPGA RAL
|
||||
*/
|
||||
#define RAL_TRX_CCA_MODE4 4
|
||||
|
||||
/**@brief Maximum available value of CCA MODE for FPGA RAL
|
||||
*/
|
||||
#define RAL_TRX_CCA_MODE_MAX RAL_TRX_CCA_MODE4
|
||||
|
||||
/**@brief Maximum duration of CCA algorithm including a task scheduling
|
||||
*/
|
||||
#define RAL_LONGEST_CCA_DURATION_US 500
|
||||
|
||||
/**@brief Maximum transmit power in dBm
|
||||
*/
|
||||
#define RAL_MAXIMUM_TX_POWER 9
|
||||
|
||||
/**@brief Maximum tolerance of transmit power in dBm
|
||||
*/
|
||||
#define RAL_TX_POWER_TOLERANCE PHY_TX_POWER_TOLERANCE_6DB
|
||||
|
||||
/**@brief Value of RF signal power (in dBm) for RSSI equals zero.
|
||||
*/
|
||||
#define RSSI_BASE_VAL 90
|
||||
|
||||
/**@brief Values above this shouldn't appear in RSSI register result.*/
|
||||
#define RSSI_REG_MAX_VAL 20
|
||||
|
||||
|
||||
/**@brief Controls whether radio module will automatically calculate Frame
|
||||
* Control Sequence field.
|
||||
*
|
||||
* @param auto_fcs_enabled if set to true, automatically generated FCS will
|
||||
* replace the last two bytes of PHY service data unit.
|
||||
*/
|
||||
void ral_auto_fcs_set(bool auto_fcs_enabled);
|
||||
|
||||
/**@brief Controls whether radio module will enter channel jamming mode.
|
||||
*
|
||||
* @param jamming_enabled if set to true, radio will perform jamming on current
|
||||
* channel and energy. No data transmission can be done
|
||||
* while jamming is enabled.
|
||||
*/
|
||||
void ral_jam_control_set(bool jamming_enabled);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif// RAL_API_SPEC_H_INCLUDED
|
|
@ -0,0 +1,96 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 RAL_FSM_H_INCLUDED
|
||||
#define RAL_FSM_H_INCLUDED
|
||||
|
||||
#include "sys_fsm.h"
|
||||
|
||||
/**
|
||||
* @defgroup ral_api_fsm RAL FSM API
|
||||
* @ingroup ral_api
|
||||
* @{
|
||||
*/
|
||||
|
||||
// list of possible events
|
||||
typedef enum
|
||||
{
|
||||
E_RESET,
|
||||
E_TRX_END, /**< Radio signals that TX or RX is complete.*/
|
||||
E_TX_REQ, /**< Initiates upload of a frame into radio memory and
|
||||
transmission of it into air.*/
|
||||
E_TRX_OFF,
|
||||
E_TX_ON,
|
||||
E_FORCE_TX_ON,
|
||||
E_RX_ON,
|
||||
} ral_fsm_events_t;
|
||||
|
||||
// states
|
||||
typedef enum
|
||||
{
|
||||
/* State symbol for short FSM debug mode */
|
||||
/* I */ S_TRX_OFF,
|
||||
/* J */ S_TX_ON,
|
||||
/* */ S_BUSY_TX,
|
||||
/* G */ S_RX_ON,
|
||||
/* B */ S_BUSY_RX,
|
||||
} ral_fsm_states_t;
|
||||
|
||||
/**@brief Reads current state of RAL state machine.
|
||||
*
|
||||
* @return Current state.
|
||||
*/
|
||||
ral_fsm_states_t ral_fsm_current_state_get(void);
|
||||
|
||||
/**@brief Initializes finite state machine of radio chip.*/
|
||||
void ral_fsm_init(void);
|
||||
|
||||
/**@brief Sends new event to radio FSM. This function is used for
|
||||
* changing radio state.
|
||||
*
|
||||
* @param event - event id for FSM.
|
||||
* @param p_data - pointer to event specific data (expects pointer to ral_mem_t).
|
||||
*/
|
||||
void ral_fsm_event_post(ral_fsm_events_t event, void * p_data);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* RAL_FSM_H_INCLUDED */
|
|
@ -0,0 +1,88 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 RAL_FSM_PRIVATE_H_INCLUDED
|
||||
#define RAL_FSM_PRIVATE_H_INCLUDED
|
||||
|
||||
#include "nrf52840.h"
|
||||
#include "nrf52840_bitfields.h"
|
||||
|
||||
/**
|
||||
* @defgroup ral_api_fsm_private RAL FSM private API
|
||||
* @ingroup ral_api
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @brief Private RAL function. Sets radio module into TRX_OFF mode if
|
||||
* it was in RX or TX mode. */
|
||||
void ral_fsm_a_trx_off(void * p_data);
|
||||
|
||||
/** @brief Private RAL function. Sets radio module into TRX_OFF mode if
|
||||
* it was in BUSY_RX or BUSY_TX mode. */
|
||||
void ral_fsm_a_force_trx_off(void * p_data);
|
||||
|
||||
/** @brief Private RAL function. Switches radio module from TRX_OFF
|
||||
* to TX_ON mode. */
|
||||
void ral_fsm_a_tx_on(void * p_data);
|
||||
|
||||
/** @brief Private RAL function. Switches radio module from TRX_OFF
|
||||
* to RX_ON mode. */
|
||||
void ral_fsm_a_rx_on(void * p_data);
|
||||
|
||||
/** @brief Private RAL function. Switches radio module from TX_ON
|
||||
* to RX_ON mode. */
|
||||
void ral_fsm_a_tx_to_rx(void * p_data);
|
||||
|
||||
/** @brief Private RAL function. Switches radio module from RX_ON
|
||||
* to TX_ON mode. */
|
||||
void ral_fsm_a_rx_to_tx(void * p_data);
|
||||
|
||||
/** @brief Private RAL function. Switches radio module from TRX_OFF
|
||||
* to channel jamming mode. */
|
||||
void ral_jamming_on(void);
|
||||
|
||||
/** @brief Private RAL function. Switches radio module from channel jamming
|
||||
* mode to TRX_OFF state. */
|
||||
void ral_jamming_off(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* RAL_FSM_PRIVATE_H_INCLUDED */
|
|
@ -0,0 +1,65 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 RAL_IRQ_HANDLERS_H_INCLUDED
|
||||
#define RAL_IRQ_HANDLERS_H_INCLUDED
|
||||
|
||||
#define RAL_NRF_BCC_COMPARE_VALUE 32
|
||||
#define RAL_NRF_BCC_COMPARE_NONE (RAL_NRF_BCC_COMPARE_VALUE + 16)
|
||||
#define RAL_NRF_BCC_COMPARE_SHORT (RAL_NRF_BCC_COMPARE_VALUE + 32)
|
||||
#define RAL_NRF_BCC_COMPARE_LONG (RAL_NRF_BCC_COMPARE_VALUE + 80)
|
||||
|
||||
/**
|
||||
* @defgroup ral_api_irq_handlers RAL auxiliary functions
|
||||
* @ingroup ral_api
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**@brief RAL IRQ handler symbol importer (dummy function).
|
||||
*
|
||||
* @details This function is only used to correctly import
|
||||
* RADIO_IRQHandler symbol.
|
||||
*/
|
||||
void ral_irq_handler_import(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif// RAL_IRQ_HANDLERS_H_INCLUDED
|
|
@ -0,0 +1,69 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 RAL_INIT_H_INCLUDED
|
||||
#define RAL_INIT_H_INCLUDED
|
||||
|
||||
/**
|
||||
* @defgroup ral_api_init RAL RF initialization API
|
||||
* @ingroup ral_api
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**@brief Initializes radio transceiver.
|
||||
*/
|
||||
void ral_rf_init(void);
|
||||
|
||||
/**@brief Channel number setting.
|
||||
*
|
||||
* @param channel_num - channel number
|
||||
*/
|
||||
void ral_rf_channel_set(uint8_t channel_num);
|
||||
|
||||
/**@brief Channel number getting.
|
||||
*
|
||||
* @return channel number
|
||||
*/
|
||||
uint8_t ral_rf_channel_get(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* RAL_INIT_H_INCLUDED */
|
|
@ -0,0 +1,230 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 RAL_API_H_INCLUDED
|
||||
#define RAL_API_H_INCLUDED
|
||||
|
||||
#include "ral_api_spec.h"
|
||||
#include "sys_time.h"
|
||||
#include "phy_common.h"
|
||||
#include "phy_pd_data.h"
|
||||
#include "mac_common.h"
|
||||
#include "mac_mlme_pib.h"
|
||||
#include "mac_time.h"
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
/**@file ral_api.h
|
||||
*
|
||||
* @defgroup ral_api Radio Abstraction Layer common API
|
||||
* @ingroup ral_15_4
|
||||
* @{
|
||||
*
|
||||
* @brief Radio abstraction layer common interface.
|
||||
*
|
||||
* @details These are requirements for the implementation code:
|
||||
*
|
||||
* - no frames must be received between new frame indication and
|
||||
* a call to ral_data_ind_read.
|
||||
*/
|
||||
|
||||
// various constants to use with MAC/PHY header parsing
|
||||
#define PHR_POS 0
|
||||
#define PHR_SIZE 1
|
||||
#define CRC_SIZE 2
|
||||
#define MAC_FRAME_CTRL_POS 0
|
||||
#define MAC_FRAME_CTRL_SIZE 2
|
||||
#define ACK_REQUEST_MASK 0x20
|
||||
#define SEQ_NUM_POS (MAC_FRAME_CTRL_POS + MAC_FRAME_CTRL_SIZE)
|
||||
#define ACK_PD_BIT_MASK 0x0010
|
||||
|
||||
#define FRAME_TYPE_MASK 0x0007
|
||||
#define FRAME_TYPE_BEACON 0x0000
|
||||
#define FRAME_TYPE_DATA 0x0001
|
||||
#define FRAME_TYPE_ACK 0x0002
|
||||
#define FRAME_TYPE_COMMAND 0x0003
|
||||
|
||||
#define FRAME_PENDING_MASK 0x0010
|
||||
|
||||
/**@brief RAL atomic section */
|
||||
typedef volatile uint8_t ral_atomic_t;
|
||||
|
||||
// private RAL data
|
||||
typedef struct
|
||||
{
|
||||
volatile uint8_t tx_seq_num;
|
||||
volatile bool ack_needed;
|
||||
volatile bool waiting_for_ack;
|
||||
volatile ral_atomic_t ral_atomic;
|
||||
volatile mac_timestamp_t received_frame_timestamp;
|
||||
volatile bool spi_transfer;
|
||||
volatile bool cca_performing;
|
||||
#if defined(AT86RF231)
|
||||
volatile int8_t ed_value;
|
||||
volatile bool unread_frame; /** This flag is used to deny transmission if incoming frame
|
||||
has not been read from radio buffer.
|
||||
todo: remove this deny to accelerate data exchange.
|
||||
*/
|
||||
volatile bool is_promiscuous_mode; /**< Set to true if promiscuous mode is enabled.*/
|
||||
#elif (defined(NRF52_SERIES) || defined(NRF52))
|
||||
// pointer to free memory for rx DMA
|
||||
volatile uint8_t * p_buffer;
|
||||
volatile sys_time_t calibr_value;
|
||||
volatile uint8_t bcc_part;
|
||||
#endif
|
||||
} ral_mem_t;
|
||||
|
||||
|
||||
/**@brief Initializes radio abstraction layer.
|
||||
*/
|
||||
void ral_init(void);
|
||||
|
||||
/**@brief Resets radio abstraction layer.
|
||||
*/
|
||||
void ral_reset(void);
|
||||
|
||||
/**@brief Performs synchronous ED measurement.
|
||||
*/
|
||||
uint8_t ral_ed_perform(void);
|
||||
|
||||
/**@brief Sends request to change radio state.
|
||||
*
|
||||
* @param state - New radio state. One of...
|
||||
*
|
||||
* @return PHY_SUCCESS, if state has been successfully achieved;
|
||||
* current state, if state cannot be reached.*/
|
||||
phy_enum_t ral_state_set(const phy_enum_t state);
|
||||
|
||||
/**@brief Returns current state of radio.
|
||||
*/
|
||||
phy_enum_t ral_state_get(void);
|
||||
|
||||
/**@brief Puts radio into sleep mode
|
||||
*/
|
||||
void ral_sleep(void);
|
||||
|
||||
/**@brief Awakes a radio
|
||||
*/
|
||||
void ral_wakeup(void);
|
||||
|
||||
/**@brief Performs synchronous cca.
|
||||
*/
|
||||
phy_status_t ral_cca_perform(void);
|
||||
|
||||
/**@brief Sends PHY frame.
|
||||
*
|
||||
* @param[in] pd_data - full data frame to be send.
|
||||
*
|
||||
* @details RAL automatically adds header and FCS control bytes
|
||||
* to \a pd_data. Caller must reserve 1 byte before \a psdu
|
||||
* pointer and may leave last two bytes of payload (i.e. FCS
|
||||
* control field) uninitialized.
|
||||
*
|
||||
* RF chip or RAL code is responsible to receive an ACK frame.
|
||||
* After ACK is handled, device should be restored to the TX state.*/
|
||||
void ral_data_req(pd_data_req_t * pd_data);
|
||||
|
||||
/**@brief Reads indication frame from radio.
|
||||
*
|
||||
* @retval Pointer on the structure of a PHY data indication
|
||||
* with received frame.
|
||||
*/
|
||||
pd_data_ind_t * ral_data_ind_read(void);
|
||||
|
||||
/**@brief Enable data flow from radio hardware after it was disabled
|
||||
* by ral_data_flow_disable().
|
||||
*/
|
||||
void ral_data_flow_enable(void);
|
||||
|
||||
|
||||
/**@brief Disable data flow from radio hardware
|
||||
*/
|
||||
void ral_data_flow_disable(void);
|
||||
|
||||
|
||||
/**@brief This function is used to set attribute from MAC or PHY layer
|
||||
* without checking of its boundaries.
|
||||
*
|
||||
* @param id - one of #MAC_SHORT_ADDRESS, #MAC_EXTENDED_ADDRESS, #MAC_PAN_ID
|
||||
* and some other values.
|
||||
* @param p_value - pointer to new value.
|
||||
*/
|
||||
void ral_attribute_set(uint8_t id, const void * p_value);
|
||||
|
||||
|
||||
/**@brief This function is used to get a copy of attribute value stored inside
|
||||
* radio module.
|
||||
*
|
||||
* @param[in] id - one of #PHY_CURRENT_CHANNEL_ID, #PHY_TRANSMIT_POWER_ID or
|
||||
* #PHY_CCA_MODE_ID. Other attributes are not supported.
|
||||
* @param[out] p_attr_value - pointer to value to get.
|
||||
*/
|
||||
void ral_attribute_get(uint8_t id, void * p_attr_value);
|
||||
|
||||
/**@brief This function is used to define frame start time by it's size
|
||||
* and the timestamp, when RX IRQ has been received.
|
||||
*
|
||||
* @param irq_time - moment when IRQ has been received.
|
||||
* @param frame_size - size of received frame in bytes.
|
||||
*
|
||||
* @retval MAC timestamp when PHY header has been started to receive.
|
||||
*/
|
||||
mac_timestamp_t ral_rx_start_time(mac_timestamp_t irq_time, uint8_t frame_size);
|
||||
|
||||
/**@brief This function performs RSSI.
|
||||
*
|
||||
* @return RSSI sample value.
|
||||
*/
|
||||
uint8_t ral_rssi_get(void);
|
||||
|
||||
/**@brief This function calculates the adjusted RSSI value using a temperature
|
||||
* correction factor.
|
||||
*
|
||||
* @param[in] rssi - RSSI sample value (as returned by @ref ral_rssi_get).
|
||||
* @param[in] temp - Temperature value in °C.
|
||||
*
|
||||
* @return Temperature-corrected RSSI value.
|
||||
*/
|
||||
uint8_t ral_rssi_corrected_get(uint8_t rssi, int8_t temp);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* RAL_API_H_INCLUDED */
|
|
@ -0,0 +1,128 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SEC_AES_CCM_H_INCLUDED
|
||||
#define SEC_AES_CCM_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the AES CCM encryption/decryption routines and necessary types.
|
||||
* It also contains the declaration of the Security Abstract library initialization routine.
|
||||
*
|
||||
* @defgroup sec_aes_ccm Security AES CCM declarations
|
||||
* @ingroup sec_15_4
|
||||
* @{
|
||||
* @brief Module to declare Security AES CCM API
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief AES CCM Status enumeration.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
AES_CCM_OK, /**< AES CCM operation succeeded. */
|
||||
AES_ENGINE_FAIL, /**< AES engine failed. */
|
||||
AES_CCM_FAIL, /**< CCM algorithm failed. */
|
||||
AES_CCM_AUTH_FAIL /**< CCM authentication failed. */
|
||||
} sec_aes_ccm_status_t;
|
||||
|
||||
/**
|
||||
* @brief AES CCM request.
|
||||
*
|
||||
* @details The AES CCM request primitive is issued by the AES user.
|
||||
* There are two use cases for the request:
|
||||
* The first one is to encrypt the user text with some given key.
|
||||
* The second one is to decrypt the cipher text against the key.
|
||||
* The encrypted or decrypted data is stored in text_data.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Counted authentication tag. */
|
||||
uint8_t * mic;
|
||||
/** Security level identifier. */
|
||||
uint8_t level;
|
||||
/** A 128-bit-long string to be used as a key. Each entity must have evidence that access
|
||||
* to this key is restricted to the entity itself and its intended key sharing group member(s). */
|
||||
uint8_t * key;
|
||||
/** A nonce N of 15 - L octets. Within the scope of any encryption key, the nonce value must be unique. */
|
||||
uint8_t * nonce;
|
||||
/** An octet string representing plain text data in case of encryption and cipher text data
|
||||
* in case of decryption. */
|
||||
uint8_t * text_data;
|
||||
/** Text data length. */
|
||||
uint8_t text_data_len;
|
||||
/** Octet string representing input data to perform authentication. */
|
||||
uint8_t * auth_data;
|
||||
/** Auth data length. */
|
||||
uint8_t auth_data_len;
|
||||
} sec_aes_ccm_req_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Function for initializing the security abstraction layer.
|
||||
*/
|
||||
void sec_init(void);
|
||||
|
||||
/**
|
||||
* @brief AES CCM encryption transformation.
|
||||
*
|
||||
* @details Performs synchronous encryption of data.
|
||||
*
|
||||
* @param req Encryption request structure.
|
||||
* @return AES_CCM_OK on success, otherwise an implementation defined error.
|
||||
*/
|
||||
sec_aes_ccm_status_t sec_aes_ccm_enc(sec_aes_ccm_req_t * req);
|
||||
|
||||
|
||||
/**
|
||||
* @brief AES CCM decryption transformation.
|
||||
*
|
||||
* @details Performs synchronous decryption of a cipher.
|
||||
*
|
||||
* @param req Decryption request structure.
|
||||
* @return AES_CCM_OK on success, otherwise an implementation defined error.
|
||||
*/
|
||||
sec_aes_ccm_status_t sec_aes_ccm_dec(sec_aes_ccm_req_t * req);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SEC_AES_CCM_H_INCLUDED */
|
|
@ -0,0 +1,75 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SEC_AES_ENTITY_H_INCLUDED
|
||||
#define SEC_AES_ENTITY_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declaration of the AES encryption routine.
|
||||
* It also contains the declaration of the AES entity initialization routine.
|
||||
*
|
||||
* @defgroup aes_entity Security AES entity declarations
|
||||
* @ingroup sec_15_4
|
||||
* @{
|
||||
* @brief Module to declare AES entity API.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Function for initializing the AES ECB module.
|
||||
*/
|
||||
void aes_entity_init(void);
|
||||
|
||||
/**
|
||||
* @brief AES encryption.
|
||||
*
|
||||
* @details Performs synchronous encryption of text against the key.
|
||||
* Encrypted data is stored to text memory.
|
||||
*
|
||||
* @param key Pointer to a 128-bit key.
|
||||
* @param text Pointer to a 128-bit plain text data.
|
||||
*/
|
||||
void aes_handle(uint8_t * key, uint8_t * text);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SEC_AES_ENTITY_H_INCLUDED */
|
|
@ -0,0 +1,95 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_CRC_H_INCLUDED
|
||||
#define SYS_CRC_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the CRC computing routines and necessary macros/types.
|
||||
*
|
||||
* @defgroup sys_crc System CRC API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module to declare System CRC API.
|
||||
* @details The CRC module implements a set of routines to compute the 16-bit CRC value for octet arrays.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Defines an initial value for the CRC sum.
|
||||
*/
|
||||
#define SYS_CRC_INIT 0
|
||||
|
||||
/**
|
||||
* @brief CRC value type. This module uses 16-bit CRC.
|
||||
*/
|
||||
typedef uint16_t sys_crc_t;
|
||||
|
||||
/**
|
||||
* @brief Function for computing CRC value for given data.
|
||||
*
|
||||
* @param[in] p_data Pointer to data to compute.
|
||||
* @param[in] length Length of data.
|
||||
*
|
||||
* @return Returns the CRC value for input data.
|
||||
*/
|
||||
sys_crc_t sys_crc_calc(const uint8_t * p_data, size_t length);
|
||||
|
||||
/**
|
||||
* @brief Function for updating the CRC value taking into the account the previously counted value.
|
||||
*
|
||||
* @details This function is used when input data is represented by several pieces.
|
||||
* Consequently, a call to this function for each piece will give a correct
|
||||
* total CRC value.
|
||||
*
|
||||
* @param[in] current_crc Previously counted CRC value. Should be SYS_CRC_INIT for the first piece.
|
||||
* @param[in] p_data Pointer to the current piece of data.
|
||||
* @param[in] length Length of the current piece of data.
|
||||
*
|
||||
* @return Returns the updated CRC value.
|
||||
*/
|
||||
sys_crc_t sys_crc_continue(sys_crc_t current_crc, const uint8_t * p_data, size_t length);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SYS_CRC_H_INCLUDED */
|
|
@ -0,0 +1,180 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_DEBUG_H_INCLUDED
|
||||
#define SYS_DEBUG_H_INCLUDED
|
||||
|
||||
|
||||
#include "hal_debug_interface.h"
|
||||
#include "hal_trace_interface.h"
|
||||
#include <stdbool.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
/* This header file contains macros for debugging. */
|
||||
#ifndef __FILENAME__
|
||||
#define __FILENAME__ __FILE__
|
||||
#endif // __FILENAME__
|
||||
|
||||
#ifndef ASSERT
|
||||
#ifdef CONFIG_DEBUG
|
||||
#define ASSERT(CONDITION_STATEMENT) \
|
||||
do \
|
||||
{ \
|
||||
bool LOCAL_CONDITION_CHECK = (CONDITION_STATEMENT); \
|
||||
if (LOCAL_CONDITION_CHECK != true) \
|
||||
{ \
|
||||
sys_assert_handler((#CONDITION_STATEMENT), __LINE__, __FILENAME__); \
|
||||
} \
|
||||
} while (0)
|
||||
#else
|
||||
|
||||
#define ASSERT(CONDITION_STATEMENT)
|
||||
|
||||
#endif // CONFIG_DEBUG
|
||||
#endif // ASSERT
|
||||
|
||||
#ifndef ASSERT_INFO
|
||||
#ifdef CONFIG_DEBUG
|
||||
#define ASSERT_INFO(CONDITION_STATEMENT, INFO_FMT, ...) \
|
||||
do \
|
||||
{ \
|
||||
bool LOCAL_CONDITION_CHECK = (CONDITION_STATEMENT); \
|
||||
if (LOCAL_CONDITION_CHECK != true) \
|
||||
{ \
|
||||
sys_assert_info_handler((#CONDITION_STATEMENT), __LINE__, __FILENAME__, \
|
||||
INFO_FMT, __VA_ARGS__); \
|
||||
} \
|
||||
} while (0)
|
||||
|
||||
#else
|
||||
|
||||
#define ASSERT_INFO(CONDITION_STATEMENT, INFO_FMT, ...)
|
||||
|
||||
#endif // CONFIG_DEBUG
|
||||
#endif // ASSERT_INFO
|
||||
|
||||
#ifndef ASSERT_STATIC
|
||||
#ifdef CONFIG_DEBUG
|
||||
#define ASSERT_STATIC(e) do { enum {SA = 1/(e)}; } while (0)
|
||||
#else
|
||||
#define ASSERT_STATIC(e)
|
||||
#endif // CONFIG_DEBUG
|
||||
#endif // ASSERT_STATIC
|
||||
|
||||
/**
|
||||
* @defgroup sys_debug Debugging macros
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Functions used for debugging.
|
||||
*/
|
||||
|
||||
|
||||
/**@brief System assertion fault handler.
|
||||
*
|
||||
* @details This macro should be used whenever an assertion fault is detected.
|
||||
*
|
||||
* @param[in] CONDITION_STRING Assertion condition string, which occurred to be not true.
|
||||
*/
|
||||
#define SYS_ASSERT_HANDLER(CONDITION_STRING) \
|
||||
do \
|
||||
{ \
|
||||
sys_assert_handler(CONDITION_STRING, __LINE__, __FILE__); \
|
||||
} while (0)
|
||||
|
||||
|
||||
#ifndef TRACE_PUTS
|
||||
#ifdef CONFIG_TRACE
|
||||
#define TRACE_PUTS(s) HAL_TRACE_INTERFACE_PUTS(s)
|
||||
#else
|
||||
#define TRACE_PUTS(s)
|
||||
#endif //CONFIG_TRACE
|
||||
#endif //TRACE_PUTS
|
||||
|
||||
|
||||
#ifndef TRACE
|
||||
#ifdef CONFIG_TRACE
|
||||
#define TRACE(INFO_FMT, ...) sys_trace_handler(INFO_FMT, __VA_ARGS__)
|
||||
#else
|
||||
#define TRACE(INFO_FMT, ...)
|
||||
#endif // CONFIG_DEBUG
|
||||
#endif // TRACE
|
||||
|
||||
|
||||
/**@brief System assertion fault handler function.
|
||||
*
|
||||
* @param[in] condition Assertion condition string, which was expected to be true.
|
||||
*
|
||||
* @param[in] line Line number.
|
||||
*
|
||||
* @param[in] file File name.
|
||||
*/
|
||||
extern void sys_assert_handler(
|
||||
const char * condition, const int line, const char * file);
|
||||
|
||||
|
||||
/**@brief System assertion fault handler function with additional assertion information.
|
||||
*
|
||||
* @param[in] condition Assertion condition string, which was expected to be true.
|
||||
*
|
||||
* @param[in] line Line number.
|
||||
*
|
||||
* @param[in] file File name.
|
||||
*
|
||||
* @param[in] info_fmt Format string for additional assert information.
|
||||
*
|
||||
* @param[in] ... Arguments list corresponding to the format string.
|
||||
*/
|
||||
extern void sys_assert_info_handler(
|
||||
const char * condition, const int line, const char * file,
|
||||
const char * info_fmt, ...);
|
||||
|
||||
|
||||
/**@brief System trace output handler function.
|
||||
*
|
||||
* @param[in] fmt Format string for trace output.
|
||||
*
|
||||
* @param[in] ... Arguments list corresponding to the format string.
|
||||
*/
|
||||
extern void sys_trace_handler(const char * fmt, ...);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_DEBUG_H_INCLUDED
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_EVENTS_H_INCLUDED
|
||||
#define SYS_EVENTS_H_INCLUDED
|
||||
|
||||
#include <stddef.h>
|
||||
#include "sys_queue.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the Events API and necessary types. The Events feature is implemented
|
||||
* using the Queue functionality.
|
||||
*
|
||||
* @defgroup sys_events System events API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module for declaring system events API.
|
||||
* @details The Events module defines some routines to subscribe/unsubscribe to/from system events. The events pool
|
||||
* can be extended by adding new events to the sys_event_id_t enumeration. The registered callbacks
|
||||
* can be called for an array of events. The callbacks can be called implicitly via posting the event by the
|
||||
* sys_event_post() routine.
|
||||
*/
|
||||
|
||||
/**@brief IDs of globally available events.
|
||||
*
|
||||
* @details Event IDs are system extension points that allow the user to implement
|
||||
* specific processing of predefined set of events, occurring in different modules.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
SYS_EVENT_FALLING_ASLEEP, /**< Falling asleep event. */
|
||||
SYS_EVENT_WAKE_UP, /**< Waking up event. */
|
||||
SYS_EVENT_OUT_OF_MEMORY, /**< Out of memory event. */
|
||||
SYS_EVENT_MEMORY_FREED, /**< Memory was freed up event. */
|
||||
|
||||
/** \note The list of system events can be extended during the implementation phase. */
|
||||
|
||||
/* The following event IDs are used only for unit testing */
|
||||
TST_EVENT_0, /**< Test event #0. */
|
||||
TST_EVENT_1, /**< Test event #1. */
|
||||
TST_EVENT_2, /**< Test event #2. */
|
||||
|
||||
#if (CONFIG_USE_SYS_TASK_NOTIFIER == 1)
|
||||
/** This event is posted when there are unhandled events available in
|
||||
* any of the schedulers.
|
||||
*/
|
||||
SYS_EVENT_NEW_TASK,
|
||||
#endif
|
||||
|
||||
SYS_EVENTS_AMOUNT
|
||||
} sys_event_id_t;
|
||||
|
||||
|
||||
/**@brief Prototype of user-implemented callback for processing an event.
|
||||
*
|
||||
* @details This callback is registered for the given event by a *_subscribe routine,
|
||||
* and is then called by the system events engine, when this event occurs.
|
||||
*
|
||||
* @param[in] p_data Pointer to the data, specific for this event.
|
||||
*/
|
||||
typedef void (* sys_event_callback_t)(const void * p_data);
|
||||
|
||||
|
||||
/**@brief Event descriptor.
|
||||
*
|
||||
* @details This descriptor is used to subscribe/unsubscribe to/from the event.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Service field. */
|
||||
sys_queue_item_t queue_item;
|
||||
|
||||
/** ID of the event to which this callback is to be subscribed. */
|
||||
sys_event_id_t event_id;
|
||||
|
||||
/** Callback function which is to be called when this event occurs. */
|
||||
sys_event_callback_t callback;
|
||||
} sys_event_desc_t;
|
||||
|
||||
|
||||
/**@brief Function for initializing the global events infrastructure.
|
||||
*/
|
||||
void sys_events_init(void);
|
||||
|
||||
|
||||
/**@brief Function for subscribing to a system event.
|
||||
*
|
||||
* @param[in] p_event_desc Pointer to the event descriptor.
|
||||
*/
|
||||
void sys_event_subscribe(sys_event_desc_t * p_event_desc);
|
||||
|
||||
|
||||
/**@brief Function for unsubscribing from a system event event.
|
||||
*
|
||||
* @param[in] p_event_desc Pointer to the event descriptor.
|
||||
*/
|
||||
void sys_event_unsubscribe(sys_event_desc_t * p_event_desc);
|
||||
|
||||
|
||||
/**@brief Function for subscribing to a group of events.
|
||||
*
|
||||
* @param[in] p_desc_array Pointer to the array of event descriptors.
|
||||
* @param[in] desc_amount Amount of event descriptors in the array.
|
||||
*/
|
||||
void sys_events_array_subscribe(sys_event_desc_t * p_desc_array, size_t desc_amount);
|
||||
|
||||
|
||||
/**@brief Function for unsubscribing from the group of events.
|
||||
*
|
||||
*
|
||||
* @param[in] p_desc_array Pointer to the array of event descriptors.
|
||||
* @param[in] desc_amount Amount of the event descriptors in the array.
|
||||
*/
|
||||
void sys_events_array_unsubscribe(sys_event_desc_t * p_desc_array, size_t desc_amount);
|
||||
|
||||
|
||||
/**@brief Function for posting an event.
|
||||
*
|
||||
* @details This function is used to notify all the subscribers of the given events via
|
||||
* their callbacks, when the given event occurs.
|
||||
*
|
||||
* @param[in] event_id ID of the event to be posted.
|
||||
* @param[in] p_data Pointer to be passed to the event handlers' callbacks.
|
||||
*/
|
||||
void sys_event_post(sys_event_id_t event_id, const void * p_data);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_EVENTS_H_INCLUDED
|
|
@ -0,0 +1,286 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_FSM_H_INCLUDED
|
||||
#define SYS_FSM_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the Finite State Machine (FSM) primitives and necessary types.
|
||||
*
|
||||
* @defgroup sys_fsm Finite State Machine API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module to declare Finite State Machine API
|
||||
* @details The FSM module implements the Finite State Machine abstraction. The user is intended to implement a transition
|
||||
* table of states with guards and actions in order to represent some event-driven subject. When a table is
|
||||
* implemented, call sys_fsm_init() to initialize the FSM. After that, the only routine to
|
||||
* work with FSM is sys_fsm_event_post().
|
||||
*/
|
||||
|
||||
/**@brief Fixed-size type for FSM state ID.
|
||||
*/
|
||||
typedef uint8_t sys_fsm_state_id_t;
|
||||
|
||||
|
||||
/**@brief Fixed-size type for FSM event ID.
|
||||
*/
|
||||
typedef uint8_t sys_fsm_event_id_t;
|
||||
|
||||
|
||||
/**@brief Fixed-size type for FSM guard condition ID.
|
||||
*/
|
||||
typedef uint8_t sys_fsm_guard_id_t;
|
||||
|
||||
|
||||
/**@brief Fixed-size type for FSM action ID.
|
||||
*/
|
||||
typedef uint8_t sys_fsm_action_id_t;
|
||||
|
||||
|
||||
/**@brief FSM transition description (item of FSM transition table).
|
||||
*
|
||||
* @details When an event with given event_id occurs, the guard condition with guard_id
|
||||
* is checked, and if it returns true, the action with action_id is performed,
|
||||
* and state machine is switched to the state with new_state_id.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
sys_fsm_event_id_t event_id; /**< FSM event ID. */
|
||||
sys_fsm_guard_id_t guard_id; /**< FSM guard ID. */
|
||||
sys_fsm_action_id_t action_id; /**< FSM action ID. */
|
||||
sys_fsm_state_id_t new_state_id; /**< New state ID. */
|
||||
#if defined(CONFIG_FSM_DEBUG)
|
||||
const char * debug_string;
|
||||
#endif
|
||||
} sys_fsm_transition_t;
|
||||
|
||||
|
||||
/**@brief FSM transition declaration (item of FSM transition table).
|
||||
*/
|
||||
#if defined(CONFIG_FSM_DEBUG)
|
||||
# define SYS_FSM_TRANSITION(event_id, guard_id, action_id, new_state_id) \
|
||||
{(event_id), (guard_id), (action_id), (new_state_id), \
|
||||
"(" #event_id ", " #guard_id ", " #action_id " -> " #new_state_id ")"}
|
||||
#else
|
||||
# define SYS_FSM_TRANSITION(event_id, guard_id, action_id, new_state_id) \
|
||||
{(event_id), (guard_id), (action_id), (new_state_id)}
|
||||
#endif
|
||||
|
||||
|
||||
/**@brief FSM state declaration.
|
||||
*
|
||||
* @details The state is an aggregator item of the FSM transition table, aggregating
|
||||
* the transitions, declared immediately after this state declaration.
|
||||
* All transition declaration items, following the state declaration item,
|
||||
* will be aggregated in this state, until the next state declaration item,
|
||||
* or the "end of table" item.
|
||||
*/
|
||||
#define SYS_FSM_STATE(state_id) \
|
||||
{(state_id) | SYS_FSM_STATE_FLAG, 0, 0, 0}
|
||||
|
||||
|
||||
/**@brief Empty guard condition ID.
|
||||
*
|
||||
* @details Special value of the guard_id field. If it is used in transition declaration,
|
||||
* guard check will be omitted.
|
||||
*/
|
||||
#define SYS_FSM_NO_GUARD 0xFF
|
||||
|
||||
|
||||
/**@brief Empty guard condition ID (useful synonym).
|
||||
*
|
||||
* @details Special value of the guard_id field. If it is used in transition declaration,
|
||||
* guard check will be omitted.
|
||||
*/
|
||||
#define SYS_FSM_OTHERWISE 0xFF
|
||||
|
||||
|
||||
/**@brief Empty guard condition ID (useful synonym).
|
||||
*
|
||||
* @details Special value of the guard_id field. If it is used in transition declaration,
|
||||
* guard check will be omitted.
|
||||
*/
|
||||
#define SYS_FSM_ALWAYS 0xFF
|
||||
|
||||
|
||||
/**@brief Empty action ID.
|
||||
*
|
||||
* @details Special value of the action_id field. If it is used in transition declaration,
|
||||
* no action will be performed during the transition.
|
||||
*/
|
||||
#define SYS_FSM_NO_ACTION 0xFF
|
||||
|
||||
|
||||
/**@brief Same state ID.
|
||||
*
|
||||
* @details Special value of the next_state_id field. If it is used in transition
|
||||
* declaration, the current state will not be changed.
|
||||
*/
|
||||
#define SYS_FSM_SAME_STATE 0xFF
|
||||
|
||||
|
||||
/**@brief Any state ID.
|
||||
*
|
||||
* @details Special value of the event_id field. If it is used in transition
|
||||
* declaration table, then the transitions listed in this state will be applied
|
||||
* in case they have not been listed in the transition table for the
|
||||
* current FSM state.
|
||||
* Only one SYS_FSM_STATE(SYS_FSM_ANY_STATE) can be present in the transition table.
|
||||
*/
|
||||
#define SYS_FSM_ANY_STATE 0xFF
|
||||
|
||||
|
||||
/**@brief State declaration flag.
|
||||
*
|
||||
* @details Special flag of the event_id field. This flag is used to distinguish
|
||||
* between state declaration and transition declaration.
|
||||
*/
|
||||
#define SYS_FSM_STATE_FLAG 0x80
|
||||
|
||||
|
||||
/**@brief Prototype of a user-defined FSM guard condition function.
|
||||
*
|
||||
* @details You must implement a single FSM guard condition function which will
|
||||
* use an ID of the needed guard check as a parameter.
|
||||
*
|
||||
* @param[in] guard_id Guard condition ID to be checked.
|
||||
* @param[in] p_data Additional FSM specific data.
|
||||
*
|
||||
* @retval true Transition is allowed, false otherwise.
|
||||
*/
|
||||
typedef bool (* sys_fsm_guard_t)(sys_fsm_guard_id_t guard_id, void * p_data);
|
||||
|
||||
|
||||
/**@brief Prototype of a user-defined FSM action function.
|
||||
*
|
||||
* @details You must implement a single FSM action function which will
|
||||
* use an ID of the needed action as a parameter.
|
||||
*
|
||||
* @param[in] action_id Action ID to be performed.
|
||||
* @param[in] p_data Additional FSM specific data.
|
||||
*/
|
||||
typedef void (* sys_fsm_action_t)(sys_fsm_action_id_t action_id, void * p_data);
|
||||
|
||||
|
||||
/**@brief Constant FSM descriptor which can reside in read-only memory.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
#if defined(CONFIG_FSM_DEBUG)
|
||||
const char * debug_fsm_name;
|
||||
#endif
|
||||
/** Pointer to the transition table.
|
||||
*/
|
||||
const sys_fsm_transition_t * transition_table;
|
||||
|
||||
/** Number of transitions in the transition table.
|
||||
*/
|
||||
uint8_t transitions_amount;
|
||||
|
||||
/** Initial state ID.
|
||||
*/
|
||||
sys_fsm_state_id_t initial_state;
|
||||
|
||||
/** Pointer to the guard condition function.
|
||||
*/
|
||||
sys_fsm_guard_t guard;
|
||||
|
||||
/** Pointer to the action function.
|
||||
*/
|
||||
sys_fsm_action_t action;
|
||||
} sys_fsm_const_descriptor_t;
|
||||
|
||||
|
||||
/**@brief FSM dynamic descriptor, holding the current state of the FSM.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Pointer to the constant FSM descriptor which can reside in read-only memory.
|
||||
*/
|
||||
const sys_fsm_const_descriptor_t * fsm_const_desc;
|
||||
|
||||
/** Index of the "any state transitions" block.
|
||||
*/
|
||||
uint8_t any_state_transitions_index;
|
||||
|
||||
/** Current state ID.
|
||||
*/
|
||||
volatile sys_fsm_state_id_t current_state;
|
||||
|
||||
/** Recursion protection.
|
||||
*/
|
||||
volatile uint8_t recursion_protection;
|
||||
} sys_fsm_t;
|
||||
|
||||
|
||||
#if defined(CONFIG_FSM_DEBUG)
|
||||
#define FSM_DEBUG_NAME(name_string) .debug_fsm_name = name_string,
|
||||
#else
|
||||
#define FSM_DEBUG_NAME(name_string)
|
||||
#endif
|
||||
|
||||
|
||||
/**@brief Function for initializing a specific FSM.
|
||||
*
|
||||
* @param[in] p_fsm Pointer to FSM descriptor to initialize.
|
||||
* @param[in] p_fsm_const Pointer to constant FSM descriptor with transition table, etc.
|
||||
*/
|
||||
void sys_fsm_init(sys_fsm_t * p_fsm, const sys_fsm_const_descriptor_t * p_fsm_const);
|
||||
|
||||
|
||||
/**@brief Function for posting an event to FSM.
|
||||
*
|
||||
* @details This function causes FSM transition from the current state to the new state,
|
||||
* according to the transition table of this FSM.
|
||||
* The corresponding guard check and action is performed.
|
||||
*
|
||||
* @param[in] p_fsm Pointer to FSM descriptor.
|
||||
* @param[in] event_id Event ID to post.
|
||||
* @param[in] p_data Pointer to the FSM-specific data.
|
||||
*/
|
||||
void sys_fsm_event_post(sys_fsm_t * p_fsm, sys_fsm_event_id_t event_id, void * p_data);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_FSM_H_INCLUDED
|
|
@ -0,0 +1,69 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_INIT_H_INCLUDED
|
||||
#define SYS_INIT_H_INCLUDED
|
||||
|
||||
#include <stddef.h>
|
||||
|
||||
/**
|
||||
* @defgroup sys_15_4_init Initialization API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief API for initizalizing the system abstraction library.
|
||||
*/
|
||||
|
||||
/** @brief Initializes every component of this stack.
|
||||
*
|
||||
* This function must be called before using any of the components.
|
||||
*
|
||||
* @param[in] p_start Pool start address.
|
||||
* @param[in] size Size of the pool in bytes.
|
||||
*
|
||||
* @details The pool start address must be aligned on the ALIGN_VALUE boundary, which is
|
||||
* defined in @c sys_utils.h.
|
||||
* The pool size should be multiple of an ALIGN_VALUE, which is defined in @c sys_utils.h.
|
||||
*/
|
||||
void sys_init(void * p_start, size_t size);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SYS_INIT_H_INCLUDED */
|
|
@ -0,0 +1,248 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_LIST_H_INCLUDED
|
||||
#define SYS_LIST_H_INCLUDED
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the doubly linked list primitives and necessary types.
|
||||
* This implementation is Linux-proven and used in the memory management module.
|
||||
*
|
||||
* @defgroup sys_list Doubly linked list API.
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module to declare the doubly linked list API.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Internal list "head" struct.
|
||||
*/
|
||||
struct sys_list_head
|
||||
{
|
||||
struct sys_list_head * next;
|
||||
struct sys_list_head * prev;
|
||||
};
|
||||
|
||||
typedef struct sys_list_head sys_list_head_t;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initializes a list by variable name.
|
||||
* @warning this macro assumes that a list "head" (sys_list_head_t) variable
|
||||
* with name \a name is already created.
|
||||
*
|
||||
* @param[inout] name The "head" struct name.
|
||||
*/
|
||||
#define LIST_HEAD_INIT(name) { &(name), &(name) }
|
||||
|
||||
/**
|
||||
* @brief Defines and initializes a new list.
|
||||
* @details A call to this macro creates a new variable with the given name and
|
||||
* initializes it as a list "head".
|
||||
*
|
||||
* @param[inout] name The "head" struct name.
|
||||
*/
|
||||
#define LIST_HEAD(name) sys_list_head_t name = { &(name), &(name) }
|
||||
|
||||
|
||||
/**
|
||||
* @brief Initializes a list by pointer.
|
||||
*
|
||||
* @param[inout] ptr Pointer to a list.
|
||||
*/
|
||||
#define INIT_LIST_HEAD(ptr) \
|
||||
do \
|
||||
{ \
|
||||
(ptr)->prev = (ptr); \
|
||||
(ptr)->next = (ptr); \
|
||||
} while (0)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Checks if a list is empty.
|
||||
*
|
||||
* @param[in] sys_list_head Pointer to a list.
|
||||
* @return 0 if not empty, non-zero otherwise.
|
||||
*/
|
||||
#define IS_EMPTY(sys_list_head) (sys_list_head)->next == (sys_list_head)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Adds a new item to the list between \a l_prev and \a l_next elements.
|
||||
* @warning This routine assumes that \a l_next is next to \a l_prev in the list.
|
||||
* @note This is an internal helper routine which is not intended to be used by the user.
|
||||
*
|
||||
* @param[in] l_prev Pointer to the previous element.
|
||||
* @param[in] l_next Pointer to the next element.
|
||||
* @param[in] l_new Pointer to a new element.
|
||||
*/
|
||||
static inline void sys_ll_list_add(sys_list_head_t * l_prev,
|
||||
sys_list_head_t * l_next,
|
||||
sys_list_head_t * l_new)
|
||||
{
|
||||
l_new->prev = l_prev;
|
||||
l_prev->next = l_new;
|
||||
l_next->prev = l_new;
|
||||
l_new->next = l_next;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Deletes an element between \a l_prev and \a l_next elements.
|
||||
* @warning This macro assumes that \a l_next is next to \a l_prev in the list.
|
||||
* @note This is an internal helper routine which is not intended to be used by the user.
|
||||
*
|
||||
* @param[in] l_prev Pointer to the previous element.
|
||||
* @param[in] l_next Pointer to the next element.
|
||||
*/
|
||||
static inline void sys_ll_list_del(sys_list_head_t * l_next,
|
||||
sys_list_head_t * l_prev)
|
||||
{
|
||||
l_next->prev = l_prev;
|
||||
l_prev->next = l_next;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Function for adding a new item to the head of the list.
|
||||
*
|
||||
* @param[in] new Pointer to a new element.
|
||||
* @param[in] head Pointer to the list head.
|
||||
*/
|
||||
static inline void sys_list_add(sys_list_head_t * new, sys_list_head_t * head)
|
||||
{
|
||||
sys_ll_list_add(head, head->next, new);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Function for adding a new item to the tail of the list.
|
||||
*
|
||||
* @param[in] new Pointer to a new element.
|
||||
* @param[in] head Pointer to the list head.
|
||||
*/
|
||||
static inline void sys_list_add_tail(sys_list_head_t * new, sys_list_head_t * head)
|
||||
{
|
||||
sys_ll_list_add(head->prev, head, new);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Function for deleting an entry from list.
|
||||
*
|
||||
* @param[in] entry The element to delete from the list.
|
||||
*/
|
||||
static inline void sys_list_del(sys_list_head_t * entry)
|
||||
{
|
||||
sys_ll_list_del(entry->next, entry->prev);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Function for deleting an entry from the list and reinitializing it.
|
||||
*
|
||||
* @param[in] entry The element to delete from the list.
|
||||
*/
|
||||
static inline void sys_list_del_init(sys_list_head_t * entry)
|
||||
{
|
||||
sys_ll_list_del(entry->next, entry->prev);
|
||||
INIT_LIST_HEAD(entry);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Function for testing if a list is empty.
|
||||
|
||||
* @param[in] head The list to test.
|
||||
* @return 0 if not empty, non-zero otherwise.
|
||||
*/
|
||||
static inline unsigned int sys_list_empty(sys_list_head_t * head)
|
||||
{
|
||||
return IS_EMPTY(head);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Sets a pointer to a variable to the parent structure pointer using a
|
||||
* pointer to a field in this structure.
|
||||
*
|
||||
* @note This is a version of @ref GET_PARENT_BY_FIELD() extended by setting to a variable.
|
||||
*
|
||||
* @param[out] ll_ret_var Variable pointer name to return.
|
||||
* @param[in] ll_ptr Pointer to the structure field.
|
||||
* @param[in] ll_type Name of the parent structure.
|
||||
* @param[in] ll_member Name of the structure field.
|
||||
*/
|
||||
#define SYS_LIST_ENTRY(ll_ret_var, ll_ptr, ll_type, ll_member) \
|
||||
do \
|
||||
{ \
|
||||
size_t p = (size_t) ll_ptr; \
|
||||
size_t off = offsetof(ll_type, ll_member); \
|
||||
ll_ret_var = (ll_type *) (p - off); \
|
||||
} while (0)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Iterates through the list.
|
||||
* @note Use @ref SYS_LIST_FOR_EACH_SAFE() for thread-safe cases.
|
||||
*
|
||||
* @param[out] pos Iterator variable.
|
||||
* @param[in] head Pointer to the list head.
|
||||
*/
|
||||
#define SYS_LIST_FOR_EACH(pos, head) \
|
||||
for (pos = ((head)->next); \
|
||||
((pos) != (head)); \
|
||||
pos = (pos)->next)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Thread-safe version of @ref SYS_LIST_FOR_EACH().
|
||||
*
|
||||
* @param[out] ll_pos Iterator variable.
|
||||
* @param[out] ll_pos_n Temporary iterator variable (next entry).
|
||||
* @param[in] ll_head Pointer to the list head.
|
||||
*/
|
||||
#define SYS_LIST_FOR_EACH_SAFE(ll_pos, ll_pos_n, ll_head) \
|
||||
for (ll_pos = (ll_head)->next, ll_pos_n = (ll_head)->next->next; \
|
||||
(ll_pos) != (ll_head); \
|
||||
ll_pos = ll_pos_n, ll_pos_n = ll_pos->next)
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SYS_LIST_H_INCLUDED */
|
|
@ -0,0 +1,92 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_MEMORY_MANAGER_H_INCLUDED
|
||||
#define SYS_MEMORY_MANAGER_H_INCLUDED
|
||||
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the Memory manager API.
|
||||
*
|
||||
* @defgroup sys_memory_manager Memory Manager API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module to declare Memory Manager API.
|
||||
* @details The Memory Manager module implements the standard API for allocating/freeing memory chunks. The module must
|
||||
* be initialized by sys_mm_init() before a call to any alloc/free routines. The memory can be allocated by a
|
||||
* call to sys_mm_alloc() and freed by a call to sys_mm_free(). Minimal chunk of memory to allocate is one byte,
|
||||
* however the sys_mm_alloc() routine will allocate the number of bytes aligned to the length of the
|
||||
* machine word (e.g. 4 bytes for 32-bit architectures). The module is implemented using the doubly linked
|
||||
* lists API.
|
||||
*/
|
||||
|
||||
/**@brief Function for initializing the memory manager.
|
||||
* @details Initialize the memory manager pool of the 'size' bytes length at 'p_start' address.
|
||||
*
|
||||
* @param p_start Pool start address.
|
||||
* @param size Size of the pool in bytes.
|
||||
*/
|
||||
void sys_mm_init(void * p_start, size_t size);
|
||||
|
||||
|
||||
/**@brief Function for allocating memory in the pool.
|
||||
* @details Search and allocate free memory resources.
|
||||
*
|
||||
* @param[in] size Size of the requested memory.
|
||||
*
|
||||
* @retval Pointer to allocated memory,
|
||||
* NULL in case of error.
|
||||
*/
|
||||
void * sys_mm_alloc(size_t size);
|
||||
|
||||
|
||||
/**@brief Function for freeing the allocated memory.
|
||||
*
|
||||
* @param[in] p_addr Pointer to the memory to free.
|
||||
*
|
||||
*/
|
||||
void sys_mm_free(void * p_addr);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_MEMORY_MANAGER_H_INCLUDED
|
|
@ -0,0 +1,290 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_QUEUE_H_INCLUDED
|
||||
#define SYS_QUEUE_H_INCLUDED
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the primitives to work with queues and necessary types.
|
||||
*
|
||||
* @defgroup sys_queues Queue API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module to declare the queue API.
|
||||
* @details The queue module implements a set of routines to deal with queues. Before
|
||||
* any calls to its API are issued, a queue must be initialized using sys_queue_init(). The following routines
|
||||
* return queue items from different parts of an initialized queue without removing it from the queue:
|
||||
* sys_queue_front(), sys_queue_back(), sys_queue_next(), and sys_queue_at().
|
||||
* The following routines insert elements to the queue: sys_queue_push_front(),
|
||||
* sys_queue_push_back(), sys_queue_push_predicated(), sys_queue_push_predicated_force(), and sys_queue_insert().
|
||||
* The following routines remove elements from the queue: sys_queue_pop_front(), sys_queue_remove(),
|
||||
* sys_queue_remove_after(). These helper routines get information about a queue: sys_queue_size() and
|
||||
* sys_queue_is_empty(). The module also supports an iterator macro implemented by SYS_QUEUE_FOR_EACH().
|
||||
*/
|
||||
|
||||
/**@brief Queue item descriptor.
|
||||
*
|
||||
* @details In order to store any user data struct in a queue, the user struct should contain
|
||||
* a field of type 'sys_queue_item_t'. This field may be at any offset.
|
||||
* The user data item can be cast from the queue item,
|
||||
* by the \ref GET_PARENT_BY_FIELD() macro from sys_utils.h.
|
||||
*/
|
||||
typedef struct sys_queue_item_s
|
||||
{
|
||||
struct sys_queue_item_s * next;
|
||||
} sys_queue_item_t;
|
||||
|
||||
/**@brief Queue descriptor.
|
||||
*/
|
||||
typedef sys_queue_item_t sys_queue_t;
|
||||
|
||||
/**@brief Prototype of a predicate function for pushing an item into the queue.
|
||||
*
|
||||
* @details As a user of the queue library, implement the predicate function and pass it
|
||||
* as a parameter to \ref sys_queue_push_predicated(). You can choose
|
||||
* whether insertion of a new item should be done before the given existing item of
|
||||
* the queue, or not.
|
||||
*
|
||||
* @param[in] p_before_item Pointer to the existing item before which a new item
|
||||
* should be inserted.
|
||||
* @param[in] p_new_item Pointer to the item to be inserted into the queue.
|
||||
*
|
||||
* @retval true Insertion is to be done before the given item, false otherwise.
|
||||
*/
|
||||
typedef bool (* sys_queue_push_predicate_t)(
|
||||
sys_queue_item_t * p_before_item,
|
||||
sys_queue_item_t * p_new_item);
|
||||
|
||||
|
||||
/**@brief Function for initializing the queue before any other usage of the queue.
|
||||
*
|
||||
* @details Initialize (reset) the queue to its initial state. The queue becomes empty.
|
||||
*
|
||||
* @param[in] p_queue Queue to be initialized.
|
||||
*/
|
||||
void sys_queue_init(sys_queue_t * p_queue);
|
||||
|
||||
|
||||
/**@brief Function for getting the front (head) item of the queue without removing it.
|
||||
*
|
||||
* @details Return a pointer to the item from the head of the queue but leave it in the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to get the item from.
|
||||
*
|
||||
* @retval Pointer to the head item of the queue, or NULL if the queue is empty.
|
||||
*/
|
||||
sys_queue_item_t * sys_queue_front(const sys_queue_t * p_queue);
|
||||
|
||||
|
||||
/**@brief Function for getting the back (tail) item of the queue without removing it.
|
||||
*
|
||||
* @details Return a pointer to the item from the tail of the queue but leave it in the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to get the item from.
|
||||
*
|
||||
* @retval Pointer to the tail item of the queue, or NULL if the queue is empty.
|
||||
*/
|
||||
sys_queue_item_t * sys_queue_back(const sys_queue_t * p_queue);
|
||||
|
||||
|
||||
/**@brief Function for getting the item, next to the given item of the queue.
|
||||
*
|
||||
* @details Return a pointer to the next item after the given one, or NULL if the
|
||||
* given item is the last item of the queue.
|
||||
*
|
||||
* @param[in] p_queue Pointer to the queue.
|
||||
* @param[in] p_item Pointer to the item.
|
||||
*
|
||||
* @retval Pointer to the next item after the given one, or NULL if the
|
||||
* given item is the last item of the queue.
|
||||
*/
|
||||
sys_queue_item_t * sys_queue_next(const sys_queue_t * p_queue, const sys_queue_item_t * p_item);
|
||||
|
||||
|
||||
/**@brief Function for pushing an item to the front (head) of the queue.
|
||||
*
|
||||
* @details This function inserts an item to the head of the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to push the item to.
|
||||
* @param[in] p_item Item to insert to the front of the queue.
|
||||
*/
|
||||
void sys_queue_push_front(sys_queue_t * p_queue, sys_queue_item_t * p_item);
|
||||
|
||||
|
||||
/**@brief Function for pushing an item to the back (tail) of the queue.
|
||||
*
|
||||
* @details This function inserts an item to the tail of the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to push the item to.
|
||||
* @param[in] p_item Item to insert to the tail of the queue.
|
||||
*/
|
||||
void sys_queue_push_back(sys_queue_t * p_queue, sys_queue_item_t * p_item);
|
||||
|
||||
|
||||
/**@brief Function for pushing an item to the queue with a predicate.
|
||||
*
|
||||
* @details Conditionally push an item to the queue using the given predicate that tries to determine
|
||||
* the insertion position.
|
||||
*
|
||||
* @param[in] p_queue Queue to push the item to.
|
||||
* @param[in] p_item Item to be pushed.
|
||||
* @param[in] predicate Predicate to be used to find the insertion position.
|
||||
*
|
||||
* @retval true The item was inserted into the queue, false otherwise.
|
||||
*/
|
||||
bool sys_queue_push_predicated(
|
||||
sys_queue_t * p_queue,
|
||||
sys_queue_item_t * p_item,
|
||||
sys_queue_push_predicate_t predicate);
|
||||
|
||||
|
||||
/**@brief Function for pushing an item to the queue with a predicate forcing insertion to the tail if the predicate
|
||||
* fails.
|
||||
*
|
||||
* @details Unconditionally push an item to the queue using the given predicate that tries to
|
||||
* determine the insertion position.
|
||||
* If predicate returns false, then force the insertion to the tail of the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to push item to.
|
||||
* @param[in] p_item Item to be pushed.
|
||||
* @param[in] predicate Predicate to be used to find the insertion position.
|
||||
*/
|
||||
void sys_queue_push_predicated_force(
|
||||
sys_queue_t * p_queue,
|
||||
sys_queue_item_t * p_item,
|
||||
sys_queue_push_predicate_t predicate);
|
||||
|
||||
|
||||
/**@brief Function for getting and removing the front (head) item from the queue.
|
||||
*
|
||||
* @details Get an item from the head of the queue and remove it from the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to get and remove the head item from.
|
||||
*
|
||||
* @retval Pointer to the head item of queue or NULL if the queue is empty.
|
||||
*/
|
||||
sys_queue_item_t * sys_queue_pop_front(sys_queue_t * p_queue);
|
||||
|
||||
|
||||
/**@brief Function for removing an item from the queue.
|
||||
*
|
||||
* @details The given item will be removed from the queue.
|
||||
*
|
||||
* @note The complexity of this function is O(n). Use function \ref sys_queue_remove_after()
|
||||
* whenever the previous item of the queue is known.
|
||||
*
|
||||
* @param[in] p_queue Queue to remove the item from.
|
||||
* @param[in] p_item Item to remove from the queue.
|
||||
*/
|
||||
void sys_queue_remove(sys_queue_t * p_queue, sys_queue_item_t * p_item);
|
||||
|
||||
|
||||
/**@brief Function for removing the item after the given item from the queue.
|
||||
*
|
||||
* @details The item next to the given one will be removed from the queue.
|
||||
*
|
||||
* @param[in] p_queue Queue to remove the item from.
|
||||
* @param[in] p_after_item Next to this item will be removed.
|
||||
*/
|
||||
void sys_queue_remove_after(sys_queue_t * p_queue, sys_queue_item_t * p_after_item);
|
||||
|
||||
|
||||
/**@brief Function for returning the current size of a queue, i.e. number of elements inside it.
|
||||
*
|
||||
* @details This function goes through the whole queue, so it is relatively slow.
|
||||
*
|
||||
* @param[in] p_queue Queue to work with.
|
||||
*
|
||||
* @retval Number of items currently inserted into the queue.
|
||||
*/
|
||||
uint8_t sys_queue_size(const sys_queue_t * p_queue);
|
||||
|
||||
|
||||
/**@brief Function for returning a pointer to the item inside a queue represented by an index.
|
||||
*
|
||||
* @details This function searches through the whole queue, so it is relatively slow.
|
||||
*
|
||||
* @param[in] p_queue Queue to work with.
|
||||
* @param[in] index Requested index.
|
||||
*
|
||||
* @retval Pointer to the requested item or NULL if the queue size is less
|
||||
* than \a index.
|
||||
*/
|
||||
sys_queue_item_t * sys_queue_at(const sys_queue_t * p_queue, const uint8_t index);
|
||||
|
||||
|
||||
/**@brief Function for inserting an item at the specified position represented by an index in the queue.
|
||||
* If this position is too big, it is inserted to the tail of the queue.
|
||||
*
|
||||
* @details This function searches through the whole queue, so it is relatively slow.
|
||||
*
|
||||
* @param[in] p_queue Queue to insert to.
|
||||
* @param[in] p_item Item to be inserted.
|
||||
* @param[in] pos Position inside the queue (0 is the front).
|
||||
*/
|
||||
void sys_queue_insert(sys_queue_t * p_queue, sys_queue_item_t * p_item, const uint8_t pos);
|
||||
|
||||
|
||||
/**@brief Function for determining if a queue is empty.
|
||||
*
|
||||
* @param[in] p_queue Queue to be checked.
|
||||
*
|
||||
* @retval True if queue is empty, false otherwise.
|
||||
*/
|
||||
bool sys_queue_is_empty(const sys_queue_t * p_queue);
|
||||
|
||||
|
||||
/**@brief Macro for iterating through all items in the queue.
|
||||
*
|
||||
* @param[in] p_queue Pointer to the queue (sys_queue_t *).
|
||||
* @param[in] p_iterator Variable to be used as an iterator (sys_queue_item_t *).
|
||||
*/
|
||||
#define SYS_QUEUE_FOR_EACH(p_queue, p_iterator) \
|
||||
for (sys_queue_item_t * p_iterator = sys_queue_front(p_queue); \
|
||||
p_iterator != NULL; \
|
||||
p_iterator = sys_queue_next(p_queue, p_iterator))
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_QUEUE_H_INCLUDED
|
|
@ -0,0 +1,202 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_RINGBUFFER_H_INCLUDED
|
||||
#define SYS_RINGBUFFER_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the Ring buffer routines and necessary types. Please note that
|
||||
* each ring buffer element should have size of 1 byte.
|
||||
*
|
||||
* @defgroup sys_ringbuffer System Ring buffer API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module for declaring System Ring buffer API.
|
||||
* @details The Ring Buffer module implements routines to deal with the ring buffer. The following routines are supported:
|
||||
* sys_ringbuffer_insert(), sys_ringbuffer_remove() to operate with single element. The
|
||||
* sys_ringbuffer_remove_multiple() can be used to remove (read) several elements at once. The
|
||||
* sys_ringbuffer_clear(), sys_ringbuffer_init(), and sys_ringbuffer_init_over() functions are used to clean up and
|
||||
* initialize the ring buffer. Some information about the initialized ring buffer is available via the
|
||||
* following routines: sys_ringbuffer_size_get() to get the number of used elements, sys_ringbuffer_chunk_get()
|
||||
* to return the biggest, available to read, continuous chunk of elements, sys_ringbuffer_is_empty() and
|
||||
* sys_ringbuffer_is_full() to check if the ring buffer is empty/full, and sys_ringbuffer_max_size_get() to get
|
||||
* the ring buffer capacity. One of the samples for ring buffer usage is the UART implementation.
|
||||
*/
|
||||
|
||||
/** This structure holds all necessary information about a ring buffer. It is intentionally left undocumented
|
||||
* by Doxygen.
|
||||
*
|
||||
* All these fields are private and must NOT be changed by the user.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
size_t write_index;
|
||||
size_t read_index;
|
||||
uint8_t * array;
|
||||
size_t size;
|
||||
bool is_full;
|
||||
} sys_ringbuffer_t;
|
||||
|
||||
/** @brief Function for initializing an empty ring buffer over passed memory.
|
||||
*
|
||||
* @param[inout] buffer Instance of sys_ringbuffer_t that will be initialized.
|
||||
* @param[in] memory Start address of the memory region used as a ring buffer.
|
||||
* @param[in] length Size in bytes of the memory region used as a ring buffer.
|
||||
*/
|
||||
void sys_ringbuffer_init(sys_ringbuffer_t * buffer,
|
||||
const void * memory,
|
||||
const size_t length);
|
||||
|
||||
/** @brief Function for initializing a ring buffer over passed memory and marking all
|
||||
* pre_init_length elements as inserted.
|
||||
*
|
||||
* @details This function may be used to initialize a buffer with some
|
||||
* pre-initialized data in it. Passed memory region is interpreted by this function
|
||||
* as an already filled (partly or fully) ring buffer so that \a pre_init_length
|
||||
* elements are marked as inserted.
|
||||
*
|
||||
* @param[inout] buffer Instance of sys_ringbuffer_t that will be initialized.
|
||||
* @param[in] memory Start address of the memory region used as a ring buffer.
|
||||
* @param[in] pre_init_length Number of elements (bytes) that had already been in \a memory.
|
||||
* They would be inserted into the newly-initialized ring buffer in a FIFO manner.
|
||||
* @param[in] length Size of the memory region used as a ring buffer.
|
||||
*/
|
||||
void sys_ringbuffer_init_over(sys_ringbuffer_t * buffer,
|
||||
const void * memory,
|
||||
const size_t pre_init_length,
|
||||
const size_t length);
|
||||
|
||||
/** @brief Function for removing an element from a ring buffer and returning it.
|
||||
*
|
||||
* @param[inout] buf Instance of @c sys_ringbuffer_t.
|
||||
*
|
||||
* @return Value of the removed element.
|
||||
*
|
||||
* @warning This buffer has no underflow control except assert.
|
||||
*/
|
||||
uint8_t sys_ringbuffer_remove(sys_ringbuffer_t * buf);
|
||||
|
||||
/** @brief Function for quickly removing up to chunk_size elements from a ring buffer
|
||||
* and marking those elements as available in the ring buffer.
|
||||
*
|
||||
* @param[inout] buffer Instance of @c sys_ringbuffer_t.
|
||||
* @param[in] chunk_size Number of elements to release.
|
||||
*/
|
||||
void sys_ringbuffer_remove_multiple(sys_ringbuffer_t * buffer,
|
||||
const size_t chunk_size);
|
||||
|
||||
/** @brief Function for inserting a new element into a ring buffer.
|
||||
*
|
||||
* @param[inout] buffer Instance of @c sys_ringbuffer_t.
|
||||
* @param[in] data Element value to insert.
|
||||
*
|
||||
* @warning In case of overflow, this buffer will overwrite the oldest
|
||||
* element and the number of available elements will remain unchanged.
|
||||
*/
|
||||
void sys_ringbuffer_insert(sys_ringbuffer_t * buffer, const uint8_t data);
|
||||
|
||||
/** @brief Function for clearing an instance of \a sys_ringbuffer_t, making it empty.
|
||||
*
|
||||
* @param[inout] buffer Instance of @c sys_ringbuffer_t.
|
||||
*/
|
||||
void sys_ringbuffer_clear(sys_ringbuffer_t * buffer);
|
||||
|
||||
/** @brief Function for returning the number of used elements in a ring buffer instance.
|
||||
*
|
||||
* @param[inout] buf Instance of sys_ringbuffer_t.
|
||||
*
|
||||
* @return Number of elements.
|
||||
*/
|
||||
size_t sys_ringbuffer_size_get(const sys_ringbuffer_t * buf);
|
||||
|
||||
/** @brief Function for returning the biggest, available to read, continuous chunk from a ring buffer array.
|
||||
*
|
||||
* @param[inout] buffer Instance of @c sys_ringbuffer_t.
|
||||
* @param[out] chunk Pointer to a memory chunk removed from the ring buffer.
|
||||
* @param[out] chunk_size Size of the removed chunk.
|
||||
*
|
||||
* @warning The returned chunk is still part of the ring buffer. To make the chunk elements available
|
||||
* for write, call @c sys_ringbuffer_remove_multiple() after the chunk is processed.
|
||||
*/
|
||||
void sys_ringbuffer_chunk_get(sys_ringbuffer_t * buffer,
|
||||
void ** chunk,
|
||||
size_t * chunk_size);
|
||||
|
||||
/** @brief Function for checking whether a ring buffer is empty.
|
||||
*
|
||||
* @param[inout] buf Instance of @c sys_ringbuffer_t.
|
||||
*
|
||||
* @return True if the ring buffer is empty.
|
||||
*/
|
||||
static inline bool sys_ringbuffer_is_empty(const sys_ringbuffer_t * buf)
|
||||
{
|
||||
return ((buf->write_index == buf->read_index) && (!buf->is_full));
|
||||
}
|
||||
|
||||
/** @brief Function for checking whether a ring buffer is full.
|
||||
*
|
||||
* @param[inout] buf Instance of @c sys_ringbuffer_t.
|
||||
*
|
||||
* @return True if number of items in the buffer equals to (length - 1).
|
||||
*/
|
||||
static inline bool sys_ringbuffer_is_full(const sys_ringbuffer_t * buf)
|
||||
{
|
||||
return buf->is_full;
|
||||
}
|
||||
|
||||
/** @brief Function for returning number of elements that can be potentially put into the buffer.
|
||||
*
|
||||
* @param[inout] buf Instance of @c sys_ringbuffer_t.
|
||||
*
|
||||
* @return Number of elements.
|
||||
*/
|
||||
static inline size_t sys_ringbuffer_max_size_get(const sys_ringbuffer_t * buf)
|
||||
{
|
||||
return buf->size;
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SYS_RINGBUFFER_H_INCLUDED */
|
|
@ -0,0 +1,142 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_SLAB_ALLOCATOR_H_INCLUDED
|
||||
#define SYS_SLAB_ALLOCATOR_H_INCLUDED
|
||||
|
||||
#include "phy_pd_data.h"
|
||||
|
||||
#ifndef CONFIG_SLAB_FRAME_POOL_SIZE
|
||||
#define CONFIG_SLAB_FRAME_POOL_SIZE 4
|
||||
#warning "CONFIG_SLAB_FRAME_POOL_SIZE not set in .config, using default"
|
||||
#endif
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the SLAB allocator API.
|
||||
*
|
||||
* @defgroup sys_slab_allocator SLAB Allocator API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module for declaring the SLAB Allocator API
|
||||
*/
|
||||
|
||||
/**@brief The SLAB allocator buffer type (free or busy buffer).
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
SYS_SLAB_FREE_BUFFER, /**< The buffer is free */
|
||||
SYS_SLAB_BUSY_BUFFER, /**< The buffer is busy */
|
||||
} sys_slab_buffer_type_t;
|
||||
|
||||
/**@brief Initializes the SLAB allocator.
|
||||
*
|
||||
* @details Preallocates the frame pool
|
||||
*/
|
||||
void sys_sa_init(void);
|
||||
|
||||
/**@brief Resets the SLAB allocator.
|
||||
*
|
||||
* @details Clear allocated the frame pools
|
||||
*/
|
||||
void sys_sa_reset(void);
|
||||
|
||||
/**@brief Inserts item into one of the queues of the SLAB allocator.
|
||||
*
|
||||
* @details This function is used to put the item into the SLAB allocator
|
||||
* queue. Type of buffer shall be chosen.
|
||||
*
|
||||
* @param[in] type Type of an inserted buffer (free or busy).
|
||||
* @param[in] p_item Pointer to an inserted buffer.
|
||||
*/
|
||||
void sys_sa_buffer_put(sys_slab_buffer_type_t type, pd_data_ind_t * p_item);
|
||||
|
||||
/**@brief Gets item from one of the queues of the SLAB allocator.
|
||||
*
|
||||
* @details This function is used to get the item from the SLAB allocator
|
||||
* queues. Type of buffer shall be chosen. The buffer is deleted
|
||||
* from the SLAB allocator
|
||||
*
|
||||
* @param[in] type Type of a gotten buffer (free or busy).
|
||||
*
|
||||
* @retval Pointer to a gotten buffer in case of success. NULL otherwise.
|
||||
*/
|
||||
pd_data_ind_t * sys_sa_buffer_get(sys_slab_buffer_type_t type);
|
||||
|
||||
/**@brief Deletes an allocated item from the heap.
|
||||
*
|
||||
* @details This function is used to delete allocated by SLAB allocator buffer
|
||||
* from the heap. Pointer to a frame memory of an allocated item shall be used.
|
||||
*
|
||||
* @param[in] p_frame Pointer to a frame memory of an allocated item.
|
||||
*/
|
||||
void sys_sa_buffer_free(uint8_t * p_frame);
|
||||
|
||||
/**@brief Returns buffer back to queue of free buffers.
|
||||
*
|
||||
* @details This function is used to return allocated buffer back to the queue
|
||||
* without allocation and deallocation.
|
||||
*
|
||||
* @param[in] p_item Pointer to an allocated item.
|
||||
*/
|
||||
void sys_sa_buffer_release(pd_data_ind_t * p_item);
|
||||
|
||||
/**@brief Allocates memory for the queue of free buffers.
|
||||
*
|
||||
* @details This function is used to allocate buffer from heap
|
||||
* and put them into the queue
|
||||
*
|
||||
* @retval True in case of success. False otherwise.
|
||||
*/
|
||||
bool sys_sa_memory_allocate(void);
|
||||
|
||||
/**@brief Checks if there are any buffers in the SLAB allocator queue or not.
|
||||
*
|
||||
* @details Type of checked buffers shall be passed.
|
||||
*
|
||||
* @param[in] type Type of an checked buffers (free or busy).
|
||||
*
|
||||
* @retval True in case of absence of buffers. False otherwise.
|
||||
*/
|
||||
bool sys_sa_is_empty(sys_slab_buffer_type_t type);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SYS_SLAB_ALLOCATOR_H_INCLUDED */
|
|
@ -0,0 +1,155 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_SLEEP_H_INCLUDED
|
||||
#define SYS_SLEEP_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "sys_events.h"
|
||||
#include "hal_sleep.h"
|
||||
|
||||
|
||||
/** @file
|
||||
*
|
||||
* @defgroup sys_sleep Falling Asleep API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module for declaring the Falling Asleep API.
|
||||
* @details Because additional preparation may be required to be done by user modules,
|
||||
* prior to putting hardware into the sleep mode, a notification and approval mechanism
|
||||
* is provided to the user.
|
||||
* Each module that wants to be notified about the "falling asleep" event, has to subscribe
|
||||
* to the HAL_EVENT_FALLING_ASLEEP event, using sys_sleep_approver_register(), and to
|
||||
* get the unique approver's ID value.
|
||||
* In the handler of the HAL_EVENT_FALLING_ASLEEP event, the module is able to perform
|
||||
* the required preparation before falling asleep, and to approve the falling asleep request,
|
||||
* using the module unique approver ID, after all preparation to sleep is finished.
|
||||
* The hardware will fall asleep only after all the registered approvers
|
||||
* approve the fall asleep request.
|
||||
*/
|
||||
|
||||
/**@brief Approver ID typedef.
|
||||
*/
|
||||
typedef uint8_t sys_sleep_approver_id_t;
|
||||
|
||||
|
||||
/* Sanity check for CONFIG_MAX_SLEEP_APPROVERS
|
||||
*/
|
||||
#if (!defined(CONFIG_MAX_SLEEP_APPROVERS))
|
||||
# error "CONFIG_MAX_SLEEP_APPROVERS must be defined in config file"
|
||||
#elif (CONFIG_MAX_SLEEP_APPROVERS >= 256)
|
||||
# error "CONFIG_MAX_SLEEP_APPROVERS must be less than 256"
|
||||
#endif
|
||||
|
||||
|
||||
/**@brief Function for initializing the system sleep module.
|
||||
*
|
||||
* @details This function must be called before any usage of the System Sleep module.
|
||||
*/
|
||||
void sys_sleep_init(void);
|
||||
|
||||
|
||||
/**@brief Function for registering the approver of the system sleep request.
|
||||
*
|
||||
* @details After the sleep approver is registered with this function, the hardware will
|
||||
* not fall asleep without its approval.
|
||||
*
|
||||
* @param[in] p_event_falling_asleep Event descriptor, which will handle
|
||||
* the SYS_EVENT_FALLING_ASLEEP event.
|
||||
* @param[in] p_event_wake_up Event descriptor, which will handle
|
||||
* the SYS_EVENT_WAKE_UP event.
|
||||
*
|
||||
* @retval The unique approver ID, reserved for this newly-registered approver.
|
||||
* This ID will be required to approve system sleep requests by this approver module.
|
||||
*/
|
||||
sys_sleep_approver_id_t sys_sleep_approver_register(
|
||||
sys_event_desc_t * p_event_falling_asleep,
|
||||
sys_event_desc_t * p_event_wake_up);
|
||||
|
||||
|
||||
/**@brief Function for unregistering the approver of the system sleep request.
|
||||
*
|
||||
* @details After the approver is unregistered, its approval will not be
|
||||
* required to put the system into sleep mode.
|
||||
*
|
||||
* @param[in] approver_id The unique approver ID to be unregistered.
|
||||
* @param[in] p_event_falling_asleep Event descriptor to unsubscribe from
|
||||
* the SYS_EVENT_FALLING_ASLEEP event.
|
||||
* @param[in] p_event_wake_up Event descriptor to unsubscribe from
|
||||
* the SYS_EVENT_WAKE_UP event.
|
||||
*/
|
||||
void sys_sleep_approver_unregister(
|
||||
sys_sleep_approver_id_t approver_id,
|
||||
sys_event_desc_t * p_event_falling_asleep,
|
||||
sys_event_desc_t * p_event_wake_up);
|
||||
|
||||
|
||||
/**@brief Function for approving the system sleep request.
|
||||
*
|
||||
* @details This function is to be called by the registered approver
|
||||
* in order to approve putting the system into the sleep mode.
|
||||
*
|
||||
* @param[in] approver_id The unique approver ID.
|
||||
*/
|
||||
void sys_sleep_approve(sys_sleep_approver_id_t approver_id);
|
||||
|
||||
|
||||
/**@brief Function for requesting the system to safely enter into sleep mode.
|
||||
*
|
||||
* @details This function notifies all the registered sleep approvers with the
|
||||
* HAL_EVENT_FALLING_ASLEEP event, allowing them to perform all the needed preparation
|
||||
* before the hardware falls asleep. The hardware will enter sleep mode only after
|
||||
* all registered approvers approve the fall asleep request.
|
||||
*
|
||||
* @param[in] sleep_time_ms Defines sleep time in ms.
|
||||
*/
|
||||
void sys_sleep_request_ms(uint32_t sleep_time_ms);
|
||||
|
||||
|
||||
/**@brief Function for getting information about the wakeup reason.
|
||||
*
|
||||
* @retval hal_wakeup_reason Interrupt source which was the wakeup reason.
|
||||
*/
|
||||
hal_wakeup_reason_t sys_sleep_wakeup_reason(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_SLEEP_H_INCLUDED
|
|
@ -0,0 +1,121 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_TASK_SCHEDULER_H_INCLUDED
|
||||
#define SYS_TASK_SCHEDULER_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "sys_utils.h"
|
||||
#include "hal_atomic.h"
|
||||
#include "sys_events.h"
|
||||
|
||||
/** @file
|
||||
* @defgroup sys_task_scheduler Task scheduler
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module for task scheduling.
|
||||
*/
|
||||
|
||||
/**@brief Identificators for registered handlers.
|
||||
*
|
||||
* Handlers will be called from the task scheduler.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
PHY_TASK_ID,
|
||||
HAL_TASK_ID,
|
||||
#if (CONFIG_HIGHEST_LAYER_PHY == 0)
|
||||
MAC_TASK_ID,
|
||||
#endif
|
||||
APP_TASK_ID,
|
||||
SYS_TASK_ID,
|
||||
SYS_TASKS_AMOUNT
|
||||
} sys_task_ids_t;
|
||||
|
||||
/**@brief Prototype of a task handler.
|
||||
*
|
||||
* @details Handler which will be called by the scheduler.
|
||||
*/
|
||||
typedef void (* sys_task_handler_t)(void);
|
||||
|
||||
/**@brief Pending tasks.
|
||||
*
|
||||
* @details Variable which includes markers of pending tasks.
|
||||
*/
|
||||
extern volatile uint_fast16_t g_tasks;
|
||||
|
||||
/**@brief Notify task scheduler to add a task for execution.
|
||||
*
|
||||
* @details The function sets a marker for the task for execution.
|
||||
* The task handler implements a tree architecture.
|
||||
* Task handler of each layer includes handlers of the layer's components.
|
||||
*
|
||||
* @param[in] task_id Task identificator.
|
||||
*/
|
||||
static inline void sys_task_post(sys_task_ids_t task_id)
|
||||
{
|
||||
atomic_t atomic = 0;
|
||||
|
||||
hal_atomic_start(&atomic);
|
||||
g_tasks |= BIT(task_id);
|
||||
#if (CONFIG_USE_SYS_TASK_NOTIFIER == 1)
|
||||
sys_event_post(SYS_EVENT_NEW_TASK, NULL);
|
||||
#endif
|
||||
hal_atomic_end(&atomic);
|
||||
}
|
||||
|
||||
/**@brief Returns true, if there are any event flags awaiting in the system scheduler.
|
||||
*/
|
||||
static inline bool sys_tasks_pending(void)
|
||||
{
|
||||
return g_tasks != 0;
|
||||
}
|
||||
|
||||
/**@brief Handle tasks in the main function.
|
||||
*
|
||||
* @details Handle tasks in the main function.
|
||||
*/
|
||||
void sys_task_run(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_TASK_SCHEDULER_H_INCLUDED
|
|
@ -0,0 +1,180 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_TIME_H_INCLUDED
|
||||
#define SYS_TIME_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "sys_queue.h"
|
||||
|
||||
/** @file
|
||||
* This file contains declarations of the primitives to work with Time (timers) and necessary types.
|
||||
*
|
||||
* @defgroup sys_time Time API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module for declaring Time API.
|
||||
* @details The system time module implements some routines to deal with time (timers). The timer can be started by
|
||||
* sys_timer_start(), stopped by sys_timer_stop(), and adjusted after sleep by sys_timer_adjust(). Some
|
||||
* information can be acquired by sys_timer_is_started() and sys_time_get(). The correct API for implementing hardware
|
||||
* delays is sys_time_delay_us(). Note that the module must be initialized by sys_timers_init() which
|
||||
* is done by sys_init().
|
||||
*/
|
||||
|
||||
/**@brief Unsigned type of system time.
|
||||
*/
|
||||
typedef uint64_t sys_time_t;
|
||||
|
||||
/**@brief Signed type of system time.
|
||||
*/
|
||||
typedef int64_t sys_signed_time_t;
|
||||
|
||||
/**@brief Prototype of the user-defined timer callback.
|
||||
*
|
||||
* @param p_data Pointer to the data, specific for this callback.
|
||||
*/
|
||||
typedef void (* sys_timer_callback_t)(void * p_data);
|
||||
|
||||
|
||||
/**@brief System timer type (one-shot or periodic timer).
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
SYS_TIMER_ONESHOT, /**< The timer is Oneshot */
|
||||
SYS_TIMER_PERIODIC /**< The timer is Periodic */
|
||||
} sys_timer_type_t;
|
||||
|
||||
|
||||
/**@brief Timer descriptor.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
/** Service field. */
|
||||
sys_queue_item_t item;
|
||||
|
||||
/** Service field. */
|
||||
sys_time_t absolute_time;
|
||||
|
||||
/** Relevant time moment, at which this timer is programmed to be triggered,
|
||||
* measured in microseconds.
|
||||
*/
|
||||
sys_time_t interval;
|
||||
|
||||
/** Periodic or one-shot timer.
|
||||
*
|
||||
* @details If type is set to SYS_TIMER_PERIODIC, the timer will restart automatically
|
||||
* with the same period.
|
||||
*/
|
||||
sys_timer_type_t type;
|
||||
|
||||
/** Timer callback function.
|
||||
*
|
||||
* @details This function is to be called, when this timer triggers.
|
||||
*/
|
||||
sys_timer_callback_t callback;
|
||||
|
||||
/** Timer callback parameter.
|
||||
*
|
||||
* @details This pointer is to be passed to the timer callback function.
|
||||
*/
|
||||
void * p_data;
|
||||
} sys_timer_t;
|
||||
|
||||
|
||||
/**@brief Function for initializing the timers module.
|
||||
*/
|
||||
void sys_timers_init(void);
|
||||
|
||||
|
||||
/**@brief Function for starting the timer.
|
||||
*
|
||||
* @details See the description of \ref sys_timer_t fields for the details
|
||||
* on how to program the timer.
|
||||
*
|
||||
* @param[in] p_timer Pointer to a valid timer descriptor, which is filled by the user,
|
||||
* according to \ref sys_timer_t fields description.
|
||||
*/
|
||||
void sys_timer_start(sys_timer_t * p_timer);
|
||||
|
||||
|
||||
/**@brief Function for stopping the timer.
|
||||
*
|
||||
* @details This function is used to stop the timer, which was started earlier.
|
||||
* After this function is called, the timer will not fire.
|
||||
*
|
||||
* @param[in] p_timer Pointer to a valid timer descriptor.
|
||||
*/
|
||||
void sys_timer_stop(sys_timer_t * p_timer);
|
||||
|
||||
|
||||
/**@brief Function for checking if input timer has been started.
|
||||
*
|
||||
* @param[in] p_timer Pointer to a timer.
|
||||
*
|
||||
* @retval true p_timer has been started and has not been stopped yet.
|
||||
* @retval false p_timer has never been started or already timed out.
|
||||
*/
|
||||
bool sys_timer_is_started(sys_timer_t * p_timer);
|
||||
|
||||
|
||||
/**@brief Function for getting the current system time.
|
||||
*
|
||||
* @retval The current system timer counter value in microseconds.
|
||||
*/
|
||||
sys_time_t sys_time_get(void);
|
||||
|
||||
|
||||
/**@brief Function for implementing a delay for short hardware delays.
|
||||
*
|
||||
* @warning Interrupts are NOT disabled inside this function.
|
||||
*
|
||||
* @param[in] delay_us Number of microseconds to delay.
|
||||
*/
|
||||
void sys_time_delay_us(uint32_t delay_us);
|
||||
|
||||
|
||||
/**@brief Function for executing expired timers after sleep.
|
||||
*/
|
||||
void sys_timer_adjust(void);
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // SYS_TIME_H_INCLUDED
|
|
@ -0,0 +1,541 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 SYS_UTILS_H_INCLUDED
|
||||
#define SYS_UTILS_H_INCLUDED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
#include <string.h>
|
||||
#if (defined(__GNUC__) && !defined(__SES_ARM))
|
||||
#include <strings.h>
|
||||
#endif
|
||||
#ifdef __MINGW32__
|
||||
#define ffs __builtin_ffs
|
||||
#endif
|
||||
|
||||
/** @file
|
||||
* This file contains definitions of useful macros and types.
|
||||
*
|
||||
* @defgroup sys_utils System Utilities API
|
||||
* @ingroup sys_15_4
|
||||
* @{
|
||||
* @brief Module to declare System Utilities API.
|
||||
* @details The System Utilities module implements multiple useful macros and inlines for the whole stack. Including
|
||||
* this header you will get access to GET_PARENT_BY_FIELD(), FIELD_SIZE() to work with complex structures,
|
||||
* ARRAY_SIZE() for arrays, mathematics macros like IMP(), LL_MIN(), LL_MAX(), CEIL(), ROUND(), Bitmap helpers
|
||||
* and many others. The variable arguments support macros are also defined here. Some SWAP routines are implemented
|
||||
* by this module as well.
|
||||
*/
|
||||
|
||||
/**@brief Returns the pointer to the data structure
|
||||
*
|
||||
* @param[in] struct_type name of the parent structure
|
||||
* @param[in] field_name name of the structure field
|
||||
* @param[in] field_pointer pointer to the structure field
|
||||
*
|
||||
* @retval Pointer to the parent structure which includes the field.
|
||||
*/
|
||||
#define GET_PARENT_BY_FIELD(struct_type, field_name, field_pointer) \
|
||||
((struct_type*)(void*)(((uint8_t*)field_pointer) - offsetof(struct_type, field_name)))
|
||||
|
||||
|
||||
/**@brief Returns the implication of two given expressions x and y.
|
||||
* @details The implication means: if X==TRUE then Y==TRUE.
|
||||
* The formula is: (X imp Y) = ((not X) or Y)
|
||||
*/
|
||||
#define IMP(x, y) ( !(x) || (y) )
|
||||
|
||||
|
||||
/**@brief Returns the minimum of two given expressions x and y.
|
||||
*/
|
||||
#define LL_MIN(x, y) ( ((x) < (y)) ? (x) : (y) )
|
||||
|
||||
|
||||
/**@brief Returns the maximum of two given expressions x and y.
|
||||
*/
|
||||
#define LL_MAX(x, y) ( ((x) > (y)) ? (x) : (y) )
|
||||
|
||||
|
||||
/**@brief Returns the quotient of a divided by b rounded upwards to the nearest
|
||||
* integer.
|
||||
*/
|
||||
#define CEIL(a, b) ((a) ? (((a) - 1U) / (b) + 1U) : 0U)
|
||||
|
||||
|
||||
/**@brief Returns the quotient of a divided by b rounded to the nearest integer
|
||||
* according to the standard arithmetic rules: if the fractional part of (a/b) is greater
|
||||
* or equal to 0.5 then the result is rounded upwards; if the fractional part of (a/b) is
|
||||
* less then 0.5 the result is rounded downwards.
|
||||
*
|
||||
* @note Use this formula only for unsigned arguments. The formula is not compatible with
|
||||
* the signed arguments: when a and b have different signs it gives incorrect result.
|
||||
*/
|
||||
#define ROUND(a, b) ( ((a) + ((b) >> 1)) / (b) )
|
||||
|
||||
|
||||
/**@brief Declares a long bitmap named name of size bits. The size is rounded
|
||||
* upwards to come a multiple of 8.
|
||||
*/
|
||||
#define BITMAP_DECLARE(name, size) uint8_t name[CEIL(size, 8)]
|
||||
|
||||
/**@brief Clears all bits in given bitmap.
|
||||
*/
|
||||
#define BITMAP_RESET(name) memset((name), 0U, sizeof(name))
|
||||
|
||||
/**@brief Returns the value of a bit at position bit in the long bitmap named name.
|
||||
*/
|
||||
#define BITMAP_ISSET(name, bit) ( 0 != ((name)[(bit) >> 3] & (1 << ((bit) & 0x7))) )
|
||||
|
||||
/**@brief Sets the bit at position bit in the long bitmap named name.
|
||||
*/
|
||||
#define BITMAP_SET(name, bit) (name)[(bit) >> 3] |= (1 << ((bit) & 0x7))
|
||||
|
||||
/**@brief Clears the bit at position bit in the long bitmap named name.
|
||||
*/
|
||||
#define BITMAP_CLR(name, bit) (name)[(bit) >> 3] &= ~(1 << ((bit) & 0x7))
|
||||
|
||||
/**@brief Assigns the given bitmap with the second bitmap.
|
||||
*/
|
||||
#define BITMAP_ASSIGN(nameDst, nameSrc) memcpy((nameDst), (nameSrc), sizeof(nameDst))
|
||||
|
||||
/**@brief Compares two bitmaps and returns zero if they are equal.
|
||||
*/
|
||||
#define BITMAP_EQUAL(name1, name2) ((sizeof(name1) == sizeof(name2)) && \
|
||||
(memcmp((name1), (name2), sizeof(name1)) == 0))
|
||||
|
||||
/**@brief Checks number. Return true if number is power of two.
|
||||
*/
|
||||
#define LL_IS_POWER_OF_TWO(name) ((0 != (name)) && (0 == ((name)&(name - 1))))
|
||||
|
||||
/**@brief Return True if mask is fully included into a given set and False otherwise
|
||||
*/
|
||||
#define IS_SUBSET_OF(mask, set) ((mask) == ((set) & (mask)))
|
||||
|
||||
/**@brief Creates a bit mask with single set bit on the specified position.
|
||||
*/
|
||||
#define BIT(pos) (1UL << (pos))
|
||||
|
||||
/**@brief Gets the given bit in the given value
|
||||
*/
|
||||
#define BIT_GET(val, pos) ((((uint32_t)val) & BIT(pos)) != 0)
|
||||
|
||||
/**@brief Sets or clears the given bit in the given value
|
||||
*/
|
||||
#define BIT_SET(val, pos, bit) { \
|
||||
if (bit) \
|
||||
{ \
|
||||
val |= BIT(pos); \
|
||||
} \
|
||||
else \
|
||||
{ \
|
||||
val &= ~BIT(pos); \
|
||||
} \
|
||||
}
|
||||
|
||||
/**@brief Returns two to the income power.*/
|
||||
#define POWER2(n) (1ULL << (n))
|
||||
|
||||
/**@brief Creates a bit mask of specified length.
|
||||
*/
|
||||
#define BIT_MASK(len) (BIT(len) - 1UL)
|
||||
|
||||
/**@brief Creates a bit field mask of specified length and start position.
|
||||
*/
|
||||
#define BIT_FIELD_MASK(start, len) (BIT_MASK(len) << (start))
|
||||
|
||||
/**@brief Creates a bit field mask of specified length, start position and value.
|
||||
*/
|
||||
#define BIT_FIELD_VALUE(value, start, len) (((value) & BIT_MASK(len)) << (start))
|
||||
|
||||
/**@brief Extracts a bit field value of specified start position and length.
|
||||
*/
|
||||
#define GET_BITFIELD_VALUE(bitmask, start, len) (((bitmask) >> (start)) & BIT_MASK(len))
|
||||
|
||||
/**@brief Inserts a bit field value with specified start position and length.
|
||||
*/
|
||||
#define SET_BITFIELD_VALUE(bitmask, start, len, value) \
|
||||
(bitmask = (bitmask & ~BIT_FIELD_MASK(start, len)) | BIT_FIELD_VALUE(value, start, len))
|
||||
|
||||
/**@brief Extracts a mask from a BITMAP.
|
||||
* BITMAP MUST be aligned and mask length MUST be one of 2, 4, 8, 16, 32.
|
||||
*/
|
||||
#define BITMAP_MASK_GET(bitmap, bit, len) \
|
||||
GET_BITFIELD_VALUE(((uint32_t*)(bitmap))[(bit) >> 5], (bit) & 0x1F, len)
|
||||
|
||||
/**@brief Sets up a mask to a BITMAP.
|
||||
* BITMAP MUST be aligned and mask length MUST be one of 2, 4, 8, 16, 32.
|
||||
*/
|
||||
#define BITMAP_MASK_SET(bitmap, bit, len, value) \
|
||||
SET_BITFIELD_VALUE(((uint32_t*)(bitmap))[(bit) >> 5], (bit) & 0x1F, len, value)
|
||||
|
||||
/**@brief Gets amount of the arguments.
|
||||
*/
|
||||
#define VA_NARGS(...) VA_NARGS_EVAL(__VA_ARGS__)
|
||||
#define VA_NARGS_EVAL(...) VA_NARGS_IMPL(__VA_ARGS__, \
|
||||
/* 255, 254, */ 253, 252, 251, 250, 249, 248, 247, 246, 245, 244, 243, 242, 241, 240, \
|
||||
239, 238, 237, 236, 235, 234, 233, 232, 231, 230, 229, 228, 227, 226, 225, 224, \
|
||||
223, 222, 221, 220, 219, 218, 217, 216, 215, 214, 213, 212, 211, 210, 209, 208, \
|
||||
207, 206, 205, 204, 203, 202, 201, 200, 199, 198, 197, 196, 195, 194, 193, 192, \
|
||||
191, 190, 189, 188, 187, 186, 185, 184, 183, 182, 181, 180, 179, 178, 177, 176, \
|
||||
175, 174, 173, 172, 171, 170, 169, 168, 167, 166, 165, 164, 163, 162, 161, 160, \
|
||||
159, 158, 157, 156, 155, 154, 153, 152, 151, 150, 149, 148, 147, 146, 145, 144, \
|
||||
143, 142, 141, 140, 139, 138, 137, 136, 135, 134, 133, 132, 131, 130, 129, 128, \
|
||||
127, 126, 125, 124, 123, 122, 121, 120, 119, 118, 117, 116, 115, 114, 113, 112, \
|
||||
111, 110, 109, 108, 107, 106, 105, 104, 103, 102, 101, 100, 99, 98, 97, 96, \
|
||||
095, 94, 93, 92, 91, 90, 89, 88, 87, 86, 85, 84, 83, 82, 81, 80, \
|
||||
079, 78, 77, 76, 75, 74, 73, 72, 71, 70, 69, 68, 67, 66, 65, 64, \
|
||||
063, 62, 61, 60, 59, 58, 57, 56, 55, 54, 53, 52, 51, 50, 49, 48, \
|
||||
047, 46, 45, 44, 43, 42, 41, 40, 39, 38, 37, 36, 35, 34, 33, 32, \
|
||||
031, 30, 29, 28, 27, 26, 25, 24, 23, 22, 21, 20, 19, 18, 17, 16, \
|
||||
015, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0)
|
||||
|
||||
/**@brief Helper macro. Gets amount of the arguments.
|
||||
*/
|
||||
#define VA_NARGS_IMPL(_________1, _2, _3, _4, _5, _6, _7, \
|
||||
_8, _9, _10, _11, _12, _13, _14, _15, \
|
||||
__16, _17, _18, _19, _20, _21, _22, _23, \
|
||||
_24, _25, _26, _27, _28, _29, _30, _31, \
|
||||
__32, _33, _34, _35, _36, _37, _38, _39, \
|
||||
_40, _41, _42, _43, _44, _45, _46, _47, \
|
||||
__48, _49, _50, _51, _52, _53, _54, _55, \
|
||||
_56, _57, _58, _59, _60, _61, _62, _63, \
|
||||
__64, _65, _66, _67, _68, _69, _70, _71, \
|
||||
_72, _73, _74, _75, _76, _77, _78, _79, \
|
||||
__80, _81, _82, _83, _84, _85, _86, _87, \
|
||||
_88, _89, _90, _91, _92, _93, _94, _95, \
|
||||
__96, _97, _98, _99, _100, _101, _102, _103, \
|
||||
_104, _105, _106, _107, _108, _109, _110, _111, \
|
||||
_112, _113, _114, _115, _116, _117, _118, _119, \
|
||||
_120, _121, _122, _123, _124, _125, _126, _127, \
|
||||
_128, _129, _130, _131, _132, _133, _134, _135, \
|
||||
_136, _137, _138, _139, _140, _141, _142, _143, \
|
||||
_144, _145, _146, _147, _148, _149, _150, _151, \
|
||||
_152, _153, _154, _155, _156, _157, _158, _159, \
|
||||
_160, _161, _162, _163, _164, _165, _166, _167, \
|
||||
_168, _169, _170, _171, _172, _173, _174, _175, \
|
||||
_176, _177, _178, _179, _180, _181, _182, _183, \
|
||||
_184, _185, _186, _187, _188, _189, _190, _191, \
|
||||
_192, _193, _194, _195, _196, _197, _198, _199, \
|
||||
_200, _201, _202, _203, _204, _205, _206, _207, \
|
||||
_208, _209, _210, _211, _212, _213, _214, _215, \
|
||||
_216, _217, _218, _219, _220, _221, _222, _223, \
|
||||
_224, _225, _226, _227, _228, _229, _230, _231, \
|
||||
_232, _233, _234, _235, _236, _237, _238, _239, \
|
||||
_240, _241, _242, _243, _244, _245, _246, _247, \
|
||||
_248, _249, _250, _251, _252, _253, /* _254, _255, */\
|
||||
N, ...) N
|
||||
|
||||
/**@brief Gets amount of the arguments. Execute by compiler.
|
||||
*/
|
||||
#define VA_NARGS_COMPILE_TIME(...) ((uint8_t)(sizeof((uint8_t[]){ __VA_ARGS__ })/sizeof(uint8_t)))
|
||||
|
||||
/**@brief Swaps values.
|
||||
*/
|
||||
#define SWAP_XOR(a, b) \
|
||||
do \
|
||||
{ \
|
||||
(((b) ^= (a) ^= (b), (a) ^= (b))); \
|
||||
} while(0);
|
||||
|
||||
/**@brief Compare two number and take care of overflow threshold limit.
|
||||
*/
|
||||
#define COMPARE_WITH_THRESHOLD(a, b, threshold) \
|
||||
(((LL_MAX((a), (b)) - LL_MIN((a), (b))) < (threshold)) ? ((a) >= (b) ? 1 : 0) : ((a) > (b) ? 0 : 1))
|
||||
|
||||
|
||||
#define ROUND_MASK(a) ((a) - 1)
|
||||
#define ROUND_UP(x, a) (((x) + ROUND_MASK(a)) & ~ROUND_MASK(a))
|
||||
#define ROUND_DOWN(x, a) ((x) & ~ROUND_MASK(a))
|
||||
|
||||
/**@brief Dereferences input pointer \a y as a type \a x.
|
||||
*
|
||||
* @param[in] x type name.
|
||||
* @param[in] y pointer name.
|
||||
*/
|
||||
#define DEREF_VOID_PTR_AS(x, y) (*(x *)y)
|
||||
|
||||
/**@brief Extends some bit value to the left extending 2's complement value
|
||||
* to 8-bit length.
|
||||
*
|
||||
* @param[out] result variable, where result is store to.
|
||||
* @param[in] x input value.
|
||||
* @param[in] sign_pos an integer in range 2..6 specifying bit position of sign bit.
|
||||
*/
|
||||
#define SIGN_EXTENSION(result, x, sign_pos) \
|
||||
do \
|
||||
{ \
|
||||
result = x & (1 << sign_pos) ? \
|
||||
x | (~((1 << (sign_pos + 1)) - 1)) : \
|
||||
x & ((1 << (sign_pos + 1)) - 1); \
|
||||
} while (0)
|
||||
|
||||
/**@brief Clears some most significant bits of integer value reducing it precision.
|
||||
* Name and interface of the macro emphasizes complementary action to #SIGN_EXTENSION.
|
||||
*
|
||||
* @param[out] result variable, where result is store to.
|
||||
* @param[in] x input value.
|
||||
* @param[in] sign_pos an integer in range 2..6 specifying bit position of sign bit.
|
||||
*/
|
||||
#define SIGN_COMPRESSION(result, x, sign_pos) \
|
||||
do \
|
||||
{ \
|
||||
result = x & ((1 << (sign_pos + 1)) - 1); \
|
||||
} while (0)
|
||||
|
||||
/************************* PROTOTYPES **************************************************/
|
||||
/**@brief Swaps values of two bytes.
|
||||
*
|
||||
*/
|
||||
static inline void SWAP8(uint8_t * const x, uint8_t * const y)
|
||||
{
|
||||
uint8_t _x = *x;
|
||||
*x = *y;
|
||||
*y = _x;
|
||||
}
|
||||
|
||||
/**@brief Swaps values of two double words (DWORD).
|
||||
*
|
||||
*/
|
||||
static inline void SWAP32(uint32_t * const x, uint32_t * const y)
|
||||
{
|
||||
uint32_t _x = *x;
|
||||
*x = *y;
|
||||
*y = _x;
|
||||
}
|
||||
|
||||
/**@brief Swaps values of two arrays.
|
||||
*
|
||||
* @param[inout] x array pointer
|
||||
* @param[inout] y array pointer
|
||||
* @param[in] length amount of bytes to swap
|
||||
*/
|
||||
static inline void SWAP_ARRAYS(void * x, void * y, uint32_t length)
|
||||
{
|
||||
uint8_t *_x = (uint8_t *)(void *)x;
|
||||
uint8_t *_y = (uint8_t *)(void *)y;
|
||||
if (0x0 == ((((size_t)_x) | ((size_t)_y)) & 0x3))
|
||||
{
|
||||
size_t len4 = length / sizeof(uint32_t);
|
||||
for (size_t i = 0; i < len4; i++)
|
||||
{
|
||||
SWAP32((uint32_t*)_x, (uint32_t*)_y);
|
||||
_x += sizeof(uint32_t);
|
||||
_y += sizeof(uint32_t);
|
||||
}
|
||||
length &= 0x3;
|
||||
}
|
||||
|
||||
for (size_t i = 0; i < length; i++)
|
||||
{
|
||||
SWAP8(_x, _y);
|
||||
_x++;
|
||||
_y++;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**@brief Find the first bit of the bitmap with the given value
|
||||
* (one or zero, as specified).
|
||||
*
|
||||
* @param[in] p_bitmap Pointer to bitmap.
|
||||
* @param[in] bitmap_size Number of bits in the bitmap.
|
||||
* @param[in] bit_value The bit value to find (one or zero).
|
||||
*
|
||||
* @retval Bit position of the bit with specified value, or bitmap_size if no such bit
|
||||
* was found.
|
||||
*/
|
||||
static inline size_t bitmap_find_bit(uint8_t * p_bitmap, size_t bitmap_size, uint8_t bit_value)
|
||||
{
|
||||
#if (defined(__GNUC__) && !defined(__SES_ARM))
|
||||
if (bitmap_size <= 32)
|
||||
{
|
||||
uint32_t bitmap;
|
||||
memcpy(&bitmap, p_bitmap, sizeof(uint32_t));
|
||||
if (!bit_value)
|
||||
{
|
||||
bitmap ^= 0xFFFFFFFF;
|
||||
}
|
||||
size_t result = ffs(bitmap);
|
||||
if (result == 0 || result > bitmap_size)
|
||||
{
|
||||
return bitmap_size;
|
||||
}
|
||||
// built-in ffs implementation gives ffs(1) = 1, not 0
|
||||
return result - 1;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
for (size_t i = 0; i < bitmap_size; i++)
|
||||
{
|
||||
if (BITMAP_ISSET(p_bitmap, i) == bit_value)
|
||||
{
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return bitmap_size;
|
||||
}
|
||||
}
|
||||
|
||||
/**@brief Reverse the elements of array
|
||||
*
|
||||
* @param[in] ptr Pointer to array.
|
||||
* @param[in] len Length of array.
|
||||
*/
|
||||
static inline void array_reverse(uint8_t * ptr, size_t len)
|
||||
{
|
||||
for (size_t i = 0; i < len/2; i++)
|
||||
{
|
||||
SWAP_XOR(ptr[i], ptr[len - 1 - i]);
|
||||
}
|
||||
}
|
||||
|
||||
/**@brief Returns least significant byte of word.
|
||||
*/
|
||||
#define LSB_WORD(x) ((uint8_t)(x & 0xFF))
|
||||
|
||||
/**@brief Returns least significant byte of halfword.
|
||||
*/
|
||||
#define LSB_HWORD(x) LSB_WORD(x)
|
||||
|
||||
/**@brief Returns most significant byte of halfword.
|
||||
*/
|
||||
#define MSB_HWORD(x) ((uint8_t)(x >> 8))
|
||||
|
||||
#define ALIGN_VALUE (sizeof(size_t))
|
||||
|
||||
/**@brief Compiler-independent definitions.
|
||||
*/
|
||||
#if defined ( __CC_ARM )
|
||||
|
||||
#ifndef __WEAK
|
||||
#define __WEAK __weak
|
||||
#endif
|
||||
|
||||
#ifndef PACK
|
||||
#define PACK __attribute__ ((packed))
|
||||
#endif
|
||||
|
||||
#ifndef BEGIN_PACK
|
||||
#define BEGIN_PACK
|
||||
#endif
|
||||
|
||||
#ifndef END_PACK
|
||||
#define END_PACK
|
||||
#endif
|
||||
|
||||
#ifndef __ALIGN
|
||||
#define __ALIGN(n) __align(n)
|
||||
#endif
|
||||
|
||||
#elif defined ( __ICCARM__ )
|
||||
|
||||
#ifndef __WEAK
|
||||
#define __WEAK __weak
|
||||
#endif
|
||||
|
||||
#ifndef PACK
|
||||
#define PACK
|
||||
#endif
|
||||
|
||||
#ifndef BEGIN_PACK
|
||||
#define BEGIN_PACK _Pragma("pack(push, 1)")
|
||||
#endif
|
||||
|
||||
#ifndef END_PACK
|
||||
#define END_PACK _Pragma("pack(pop)")
|
||||
#endif
|
||||
|
||||
#ifndef __ALIGN
|
||||
#define __ALIGN(n)
|
||||
#endif
|
||||
|
||||
#elif defined ( __GNUC__ )
|
||||
|
||||
#ifndef __WEAK
|
||||
#define __WEAK __attribute__((weak))
|
||||
#endif
|
||||
|
||||
#ifndef PACK
|
||||
#define PACK __attribute__ ((packed))
|
||||
#endif
|
||||
|
||||
#ifndef BEGIN_PACK
|
||||
#define BEGIN_PACK _Pragma("pack(push,1)")
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef END_PACK
|
||||
#define END_PACK _Pragma("pack(pop)")
|
||||
#endif
|
||||
|
||||
#ifndef __ALIGN
|
||||
#define __ALIGN(n) __attribute__((aligned(n)))
|
||||
#endif
|
||||
|
||||
#elif defined ( __TASKING__ )
|
||||
|
||||
#ifndef __WEAK
|
||||
#define __WEAK __attribute__((weak))
|
||||
#endif
|
||||
|
||||
#ifndef PACK
|
||||
#define PACK __attribute__ ((packed))
|
||||
#endif
|
||||
|
||||
#ifndef BEGIN_PACK
|
||||
#define BEGIN_PACK
|
||||
#endif
|
||||
|
||||
#ifndef END_PACK
|
||||
#define END_PACK
|
||||
#endif
|
||||
|
||||
#ifndef __ALIGN
|
||||
#define __ALIGN(n) __align(n)
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif /* SYS_UTILS_H_INCLUDED */
|
|
@ -0,0 +1,110 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 STACK_802_15_4_CONFIG_H__
|
||||
#define STACK_802_15_4_CONFIG_H__
|
||||
|
||||
#define CONFIG_DEBUG 1
|
||||
#define CONFIG_MM_DEBUG 1
|
||||
#define CONFIG_TEST_CHANNEL 15
|
||||
#define CONFIG_TEST_CHANNEL_MASK (1 << CONFIG_TEST_CHANNEL)
|
||||
#define CONFIG_BEACON_ENABLED 1
|
||||
#define CONFIG_FFD_DEVICE 1
|
||||
#define CONFIG_RXE_ENABLED 1
|
||||
#define CONFIG_GTS_ENABLED 1
|
||||
#define CONFIG_SYNC_REQ_ENABLED 1
|
||||
#define CONFIG_ASSOCIATE_IND_ENABLED 1
|
||||
#define CONFIG_ORPHAN_ENABLED 1
|
||||
#define CONFIG_START_ENABLED 1
|
||||
#define CONFIG_ED_SCAN_ENABLED 1
|
||||
#define CONFIG_ACTIVE_SCAN_ENABLED 1
|
||||
#define CONFIG_PURGE_ENABLED 1
|
||||
#define CONFIG_PANID_CONFLICT_RESOLUTION_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_RESP_CMD_RX_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_RESP_CMD_TX_ENABLED 1
|
||||
#define CONFIG_DISASSOCIATION_NTF_CMD_RX_ENABLED 1
|
||||
#define CONFIG_DISASSOCIATION_NTF_CMD_TX_ENABLED 1
|
||||
#define CONFIG_DATA_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_DATA_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_PAN_CONFLICT_NTF_CMD_RX_ENABLED 1
|
||||
#define CONFIG_PAN_CONFLICT_NTF_CMD_TX_ENABLED 1
|
||||
#define CONFIG_ORPHAN_NTF_CMD_RX_ENABLED 1
|
||||
#define CONFIG_ORPHAN_NTF_CMD_TX_ENABLED 1
|
||||
#define CONFIG_BEACON_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_BEACON_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_COORD_REALIGN_CMD_RX_ENABLED 1
|
||||
#define CONFIG_COORD_REALIGN_CMD_TX_ENABLED 1
|
||||
#define CONFIG_GTS_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_GTS_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_INDIRECT_ENGINE_ENABLED 1
|
||||
#define CONFIG_ASSOCIATE_REQ_ENABLED 1
|
||||
#define CONFIG_DISASSOCIATE_ENABLED 1
|
||||
#define CONFIG_PANID_CONFLICT_ENABLED 1
|
||||
#define CONFIG_SYNC_ENABLED 1
|
||||
#define CONFIG_NONE_ADDR_SUPPORT_ENABLED 1
|
||||
#define CONFIG_PASSIVE_ORPHAN_SCAN_ENABLED 1
|
||||
#define CONFIG_PROMISCUOUS_MODE_ENABLED 1
|
||||
#define CONFIG_USE_SYS_TASK_NOTIFIER 1
|
||||
#define CONFIG_POOL_SIZE 0x2000
|
||||
#define CONFIG_SLAB_FRAME_POOL_SIZE 4
|
||||
#define CONFIG_MEMORY_POLLING_INTERVAL_MS 10
|
||||
#define CONFIG_MAX_SLEEP_APPROVERS 32
|
||||
#define CONFIG_HAL_UART_CHANNELS 1
|
||||
#define CONFIG_MAC_KEY_TABLE_SIZE 8
|
||||
#define CONFIG_MAC_DEVICE_TABLE_SIZE 8
|
||||
#define CONFIG_MAC_SECURITY_LEVEL_TABLE_SIZE 8
|
||||
#define CONFIG_MAC_KEY_ID_LOOKUP_LIST_SIZE 8
|
||||
#define CONFIG_MAC_KEY_DEVICE_LIST_SIZE 8
|
||||
#define CONFIG_MAC_KEY_USAGE_LIST_SIZE 8
|
||||
#define CONFIG_IEEE_ADDRESS 0x0123456789ABCDEFULL
|
||||
#define CONFIG_BEACON_RX_TIME 5000
|
||||
#define CONFIG_TEST_SUBTREE_MAC 1
|
||||
#define CONFIG_TEST_SUBTREE_TST 1
|
||||
#define CONFIG_COAP_TICK_INTERVAL_US 500000
|
||||
#define CONFIG_COAP_MM_SMALL_BLOCK_COUNT 32
|
||||
#define CONFIG_COAP_MM_MEDIUM_BLOCK_COUNT 32
|
||||
#define CONFIG_COAP_MM_LARGE_BLOCK_COUNT 32
|
||||
#define CONFIG_COAP_MESSAGE_QUEUE_SIZE 32
|
||||
|
||||
#endif // STACK_802_15_4_CONFIG_H__
|
||||
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,38 @@
|
|||
Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
|
||||
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.
|
|
@ -0,0 +1,111 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 STACK_802_15_4_CONFIG_H__
|
||||
#define STACK_802_15_4_CONFIG_H__
|
||||
|
||||
#define CONFIG_DEBUG 1
|
||||
#define CONFIG_MM_DEBUG 1
|
||||
#define CONFIG_TEST_CHANNEL 15
|
||||
#define CONFIG_TEST_CHANNEL_MASK (1 << CONFIG_TEST_CHANNEL)
|
||||
#define CONFIG_BEACON_ENABLED 1
|
||||
#define CONFIG_SECURE 1
|
||||
#define CONFIG_FFD_DEVICE 1
|
||||
#define CONFIG_RXE_ENABLED 1
|
||||
#define CONFIG_GTS_ENABLED 1
|
||||
#define CONFIG_SYNC_REQ_ENABLED 1
|
||||
#define CONFIG_ASSOCIATE_IND_ENABLED 1
|
||||
#define CONFIG_ORPHAN_ENABLED 1
|
||||
#define CONFIG_START_ENABLED 1
|
||||
#define CONFIG_ED_SCAN_ENABLED 1
|
||||
#define CONFIG_ACTIVE_SCAN_ENABLED 1
|
||||
#define CONFIG_PURGE_ENABLED 1
|
||||
#define CONFIG_PANID_CONFLICT_RESOLUTION_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_RESP_CMD_RX_ENABLED 1
|
||||
#define CONFIG_ASSOCIATION_RESP_CMD_TX_ENABLED 1
|
||||
#define CONFIG_DISASSOCIATION_NTF_CMD_RX_ENABLED 1
|
||||
#define CONFIG_DISASSOCIATION_NTF_CMD_TX_ENABLED 1
|
||||
#define CONFIG_DATA_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_DATA_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_PAN_CONFLICT_NTF_CMD_RX_ENABLED 1
|
||||
#define CONFIG_PAN_CONFLICT_NTF_CMD_TX_ENABLED 1
|
||||
#define CONFIG_ORPHAN_NTF_CMD_RX_ENABLED 1
|
||||
#define CONFIG_ORPHAN_NTF_CMD_TX_ENABLED 1
|
||||
#define CONFIG_BEACON_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_BEACON_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_COORD_REALIGN_CMD_RX_ENABLED 1
|
||||
#define CONFIG_COORD_REALIGN_CMD_TX_ENABLED 1
|
||||
#define CONFIG_GTS_REQ_CMD_RX_ENABLED 1
|
||||
#define CONFIG_GTS_REQ_CMD_TX_ENABLED 1
|
||||
#define CONFIG_INDIRECT_ENGINE_ENABLED 1
|
||||
#define CONFIG_ASSOCIATE_REQ_ENABLED 1
|
||||
#define CONFIG_DISASSOCIATE_ENABLED 1
|
||||
#define CONFIG_PANID_CONFLICT_ENABLED 1
|
||||
#define CONFIG_SYNC_ENABLED 1
|
||||
#define CONFIG_NONE_ADDR_SUPPORT_ENABLED 1
|
||||
#define CONFIG_PASSIVE_ORPHAN_SCAN_ENABLED 1
|
||||
#define CONFIG_PROMISCUOUS_MODE_ENABLED 1
|
||||
#define CONFIG_USE_SYS_TASK_NOTIFIER 1
|
||||
#define CONFIG_POOL_SIZE 0x2000
|
||||
#define CONFIG_SLAB_FRAME_POOL_SIZE 4
|
||||
#define CONFIG_MEMORY_POLLING_INTERVAL_MS 10
|
||||
#define CONFIG_MAX_SLEEP_APPROVERS 32
|
||||
#define CONFIG_HAL_UART_CHANNELS 1
|
||||
#define CONFIG_MAC_KEY_TABLE_SIZE 8
|
||||
#define CONFIG_MAC_DEVICE_TABLE_SIZE 8
|
||||
#define CONFIG_MAC_SECURITY_LEVEL_TABLE_SIZE 8
|
||||
#define CONFIG_MAC_KEY_ID_LOOKUP_LIST_SIZE 8
|
||||
#define CONFIG_MAC_KEY_DEVICE_LIST_SIZE 8
|
||||
#define CONFIG_MAC_KEY_USAGE_LIST_SIZE 8
|
||||
#define CONFIG_IEEE_ADDRESS 0x0123456789ABCDEFULL
|
||||
#define CONFIG_BEACON_RX_TIME 5000
|
||||
#define CONFIG_TEST_SUBTREE_MAC 1
|
||||
#define CONFIG_TEST_SUBTREE_TST 1
|
||||
#define CONFIG_COAP_TICK_INTERVAL_US 500000
|
||||
#define CONFIG_COAP_MM_SMALL_BLOCK_COUNT 32
|
||||
#define CONFIG_COAP_MM_MEDIUM_BLOCK_COUNT 32
|
||||
#define CONFIG_COAP_MM_LARGE_BLOCK_COUNT 32
|
||||
#define CONFIG_COAP_MESSAGE_QUEUE_SIZE 32
|
||||
|
||||
#endif // STACK_802_15_4_CONFIG_H__
|
||||
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,38 @@
|
|||
Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
|
||||
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.
|
|
@ -0,0 +1,66 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 <stdbool.h>
|
||||
#include "nrf_rng.h"
|
||||
#include "hal_rng.h"
|
||||
#include "sys_utils.h"
|
||||
|
||||
/**@brief Initialize hardware random generator.
|
||||
*/
|
||||
void hal_rand_init(void)
|
||||
{
|
||||
/** For future use */
|
||||
}
|
||||
|
||||
/**@brief Generates random number using hardware.
|
||||
*
|
||||
* @details The process takes about 150 us.*/
|
||||
uint8_t hal_rand_get(void)
|
||||
{
|
||||
nrf_rng_task_trigger(NRF_RNG_TASK_START);
|
||||
while(!nrf_rng_event_get(NRF_RNG_EVENT_VALRDY));
|
||||
nrf_rng_task_trigger(NRF_RNG_TASK_STOP);
|
||||
nrf_rng_event_clear(NRF_RNG_EVENT_VALRDY);
|
||||
|
||||
return nrf_rng_random_value_get();
|
||||
}
|
||||
|
|
@ -0,0 +1,62 @@
|
|||
/**
|
||||
* Copyright (c) 2016 - 2019 Nordic Semiconductor ASA and Luxoft Global Operations Gmbh.
|
||||
*
|
||||
* 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 <stdbool.h>
|
||||
#include "nrf_ecb.h"
|
||||
#include "sec_aes_entity.h"
|
||||
#include "sec_aes_ccm.h"
|
||||
#include "sys_debug.h"
|
||||
#include "sys_utils.h"
|
||||
|
||||
void aes_entity_init(void)
|
||||
{
|
||||
bool is_successful = nrf_ecb_init();
|
||||
ASSERT(is_successful);
|
||||
(void)is_successful;
|
||||
}
|
||||
|
||||
void aes_handle(uint8_t * key, uint8_t * text)
|
||||
{
|
||||
nrf_ecb_set_key(key);
|
||||
bool is_successful = nrf_ecb_crypt(text, text);
|
||||
ASSERT(is_successful);
|
||||
(void)is_successful;
|
||||
}
|
|
@ -0,0 +1,86 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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 NRF_SDH_ANT_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)
|
|
@ -0,0 +1,98 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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 NRF_SDH_ANT_ENCRYPTED_CHANNELS
|
||||
#error Undefined NRF_SDH_ANT_ENCRYPTED_CHANNELS. It should be defined in sdk_config.h file.
|
||||
#elif NRF_SDH_ANT_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 NRF_SDH_ANT_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__
|
||||
/** @} */
|
|
@ -0,0 +1,245 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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_INITIALIZED;
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
/**@brief Function for handling an ANT stack event.
|
||||
* @param[in] p_ant_evt ANT stack event.
|
||||
* @param[in] p_context Context.
|
||||
*/
|
||||
static void ant_evt_handler(ant_evt_t * p_ant_evt, void * p_context)
|
||||
{
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
NRF_SDH_ANT_OBSERVER(m_ant_observer, ANT_ENCRYPT_ANT_OBSERVER_PRIO, ant_evt_handler, NULL);
|
||||
|
||||
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)
|
|
@ -0,0 +1,241 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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 "nrf_sdh_ant.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_INITIALIZED 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 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__
|
|
@ -0,0 +1,185 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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 (NRF_SDH_ANT_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)
|
||||
{
|
||||
ant_encrypt_tracking_state_t track_state =
|
||||
ant_channel_encryp_tracking_state_get(p_ant_evt->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(p_ant_evt->channel,
|
||||
ANT_ENC_CHANNEL_STAT_NOT_TRACKING);
|
||||
break;
|
||||
|
||||
case EVENT_RX:
|
||||
ant_slave_encrypt_try_enable(p_ant_evt->channel,
|
||||
p_ant_evt->message.ANT_MESSAGE_ucMesgID);
|
||||
break;
|
||||
|
||||
case EVENT_ENCRYPT_NEGOTIATION_SUCCESS:
|
||||
m_can_enable_crypto = true;
|
||||
ant_channel_encryp_tracking_state_set(p_ant_evt->channel,
|
||||
ANT_ENC_CHANNEL_STAT_TRACKING_DECRYPTED);
|
||||
break;
|
||||
|
||||
case EVENT_ENCRYPT_NEGOTIATION_FAIL:
|
||||
m_can_enable_crypto = true;
|
||||
ant_channel_encryp_tracking_state_set(p_ant_evt->channel,
|
||||
ANT_ENC_CHANNEL_STAT_TRACKING_ENCRYPTED);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // NRF_MODULE_ENABLED(ANT_ENCRYPT_NEGOTIATION_SLAVE)
|
|
@ -0,0 +1,140 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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 "nrf_sdh_ant.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__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,399 @@
|
|||
/**
|
||||
* This software is subject to the ANT+ Shared Source License
|
||||
* www.thisisant.com/swlicenses
|
||||
* Copyright (c) Garmin Canada 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 Garmin 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 ANT-FS client protocol interface.
|
||||
* This file is based on implementation originally made in August 2012 by Garmin Canada Inc.
|
||||
* (former Dynastream Innovations Inc.)
|
||||
* @defgroup ant_fs ANT-FS client device simulator
|
||||
* @{
|
||||
* @ingroup ant_sdk_utils
|
||||
*
|
||||
* @brief The ANT-FS client device simulator.
|
||||
*
|
||||
* @note The ANT-FS Network Key is available for ANT+ Adopters. Please refer to http://thisisant.com to become an ANT+ Adopter and access the key.
|
||||
*/
|
||||
|
||||
#ifndef ANTFS_H__
|
||||
#define ANTFS_H__
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "defines.h"
|
||||
#include "sdk_config.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define ANTFS_VERSION_MAJOR 1u /**< Version major number. */
|
||||
#define ANTFS_VERSION_MINOR 0 /**< Version minor number. */
|
||||
#define ANTFS_VERSION_ITERATION 0 /**< Version iteration. */
|
||||
#define ANTFS_VERSION_TYPE 'R' /**< Version type is release. */
|
||||
#define ANTFS_VERSION_SPEC '0.AK' /**< Version of the ANT-FS Technology Specification. */
|
||||
#define ANTFS_DIR_STRUCT_VERSION 1u /**< Version of the directory file structure. */
|
||||
#define ANTFS_VERSION_DATE 20090522u /**< Version date. */
|
||||
|
||||
// ANT-FS options.
|
||||
#define ANTFS_LINK_FREQ 50u /**< RF Frequency (+2400MHz). */
|
||||
#define ANTFS_CHANNEL_TYPE CHANNEL_TYPE_MASTER /**< ANT-FS Client Channel Type. */
|
||||
#define ANTFS_AUTH_STRING_MAX 255u /**< Maximum size of authentication strings (passkey/friendly name). */
|
||||
#define ANTFS_PASSKEY_SIZE 16u /**< Passkey size. */
|
||||
#define ANTFS_FRIENDLY_NAME_MAX 16u /**< Maximum size of friendly name received from host. */
|
||||
#define ANTFS_REMOTE_FRIENDLY_NAME_MAX 16u /**< Maximum size of client's friendly name. */
|
||||
|
||||
// Beacon definitions.
|
||||
#define BEACON_PERIOD_SHIFT 0x00 /**< Shift value for masking out beacon period. */
|
||||
#define BEACON_PERIOD_MASK (0x07u << BEACON_PERIOD_SHIFT) /**< Beacon period bitmask. */
|
||||
#define BEACON_PERIOD_0_5_HZ (0x00 << BEACON_PERIOD_SHIFT) /**< Value for 0,5Hz beacon period. */
|
||||
#define BEACON_PERIOD_1_HZ (0x01u << BEACON_PERIOD_SHIFT) /**< Value for 1Hz beacon period. */
|
||||
#define BEACON_PERIOD_2_HZ (0x02u << BEACON_PERIOD_SHIFT) /**< Value for 2Hz beacon period. */
|
||||
#define BEACON_PERIOD_4_HZ (0x03u << BEACON_PERIOD_SHIFT) /**< Value for 4Hz beacon period. */
|
||||
#define BEACON_PERIOD_8_HZ (0x04u << BEACON_PERIOD_SHIFT) /**< Value for 8Hz beacon period. */
|
||||
#define PAIRING_AVAILABLE_FLAG_SHIFT 0x03u /**< Shift value for masking out pairing enabled bit. */
|
||||
#define PAIRING_AVAILABLE_FLAG_MASK (0x01u << PAIRING_AVAILABLE_FLAG_SHIFT) /**< Pairing enabled bitmask. */
|
||||
#define UPLOAD_ENABLED_FLAG_SHIFT 0x04u /**< Shift value for masking out upload enabled bit. */
|
||||
#define UPLOAD_ENABLED_FLAG_MASK (0x01u << UPLOAD_ENABLED_FLAG_SHIFT) /**< Upload enabled bitmask. */
|
||||
#define DATA_AVAILABLE_FLAG_SHIFT 0x05u /**< Shift value for masking out data available bit. */
|
||||
#define DATA_AVAILABLE_FLAG_MASK (0x01u << DATA_AVAILABLE_FLAG_SHIFT) /**< Data available bitmask. */
|
||||
|
||||
#if ANTFS_ENABLED
|
||||
// Build the default beacon settings.
|
||||
#if ANTFS_CONFIG_AUTH_TYPE_PAIRING_ENABLED
|
||||
#define ANTFS_PAIRING_BIT PAIRING_AVAILABLE_FLAG_MASK /**< Build pairing enabled default beacon setting. */
|
||||
#else
|
||||
#define ANTFS_PAIRING_BIT 0x00u /**< Build pairing disabled default beacon setting. */
|
||||
#endif // ANTFS_CONFIG_AUTH_TYPE_PAIRING_ENABLED
|
||||
#if ANTFS_CONFIG_UPLOAD_ENABLED
|
||||
#define ANTFS_UPLOAD_BIT UPLOAD_ENABLED_FLAG_MASK /**< Build upload enabled default beacon setting. */
|
||||
#else
|
||||
#define ANTFS_UPLOAD_BIT 0x00u /**< Build upload disabled default beacon setting. */
|
||||
#endif // ANTFS_CONFIG_UPLOAD_ENABLED
|
||||
|
||||
#define ANTFS_DEFAULT_BEACON (ANTFS_CONFIG_BEACON_STATUS_PERIOD | ANTFS_UPLOAD_BIT | ANTFS_PAIRING_BIT | DATA_AVAILABLE_FLAG_MASK) /**< Define the default beacon setting. */
|
||||
#endif // ANTFS_ENABLED
|
||||
|
||||
// Download/Upload responses.
|
||||
#define RESPONSE_MESSAGE_OK 0x00u /**< Download request ok. */
|
||||
#define RESPONSE_MESSAGE_NOT_EXIST 0x01u /**< File does not exist. */
|
||||
#define RESPONSE_MESSAGE_NOT_AVAILABLE 0x02u /**< File can not be read/written to (download/upload respectively). */
|
||||
#define RESPONSE_INVALID_OPERATION 0x04u /**< Request invalid. */
|
||||
// Download responses.
|
||||
#define RESPONSE_MESSAGE_NOT_READY 0x03u /**< Not ready to download. */
|
||||
#define RESPONSE_INVALID_CRC 0x05u /**< CRC incorrect. */
|
||||
// Upload responses.
|
||||
#define RESPONSE_MESSAGE_NOT_ENOUGH_SPACE 0x03u /**< Not enough space to to complete write. */
|
||||
#define RESPONSE_MESSAGE_UPLOAD_NOT_READY 0x05u /**< Not ready to upload */
|
||||
// Upload/Erase responses.
|
||||
#define RESPONSE_MESSAGE_FAIL 0x01u /**< Data File Index does not exist / Erase failed. */
|
||||
|
||||
// Directory general file flags.
|
||||
#define ANTFS_DIR_READ_MASK 0x80u /**< Read (can download). */
|
||||
#define ANTFS_DIR_WRITE_MASK 0x40u /**< Write (can upload). */
|
||||
#define ANTFS_DIR_ERASE_MASK 0x20u /**< Erase (can erase). */
|
||||
#define ANTFS_DIR_ARCHIVE_MASK 0x10u /**< Archive (has been downloaded). */
|
||||
#define ANTFS_DIR_APPEND_MASK 0x08u /**< Append (can append to file only). */
|
||||
|
||||
#define ANTFS_MAX_FILE_SIZE 0xFFFFFFFFu /**< Maximum file size, as specified by directory structure. */
|
||||
#define ANTFS_BURST_BLOCK_SIZE 16u /**< Size of each block of burst data that the client attempts to send when it processes a data request event. */
|
||||
|
||||
/**@brief ANT-FS beacon status. */
|
||||
typedef union
|
||||
{
|
||||
uint32_t status; /**< Beacon status byte 1. */
|
||||
|
||||
struct
|
||||
{
|
||||
uint8_t link_period : 3; /**< Beacon period (0.5 - 8 Hz). */
|
||||
bool is_pairing_enabled : 1; /**< Pairing is enabled/disabled. */
|
||||
bool is_upload_enabled : 1; /**< Upload is enabled/disabled. */
|
||||
bool is_data_available : 1; /**< Data is available for download / no data available. */
|
||||
uint8_t reserved : 2; /**< Reserved. */
|
||||
} parameters;
|
||||
} antfs_beacon_status_byte1_t;
|
||||
|
||||
// ANT-FS states.
|
||||
typedef enum
|
||||
{
|
||||
ANTFS_STATE_OFF, /**< Off state. */
|
||||
ANTFS_STATE_INIT, /**< Init state. */
|
||||
ANTFS_STATE_LINK, /**< Link state. */
|
||||
ANTFS_STATE_AUTH, /**< Authenticate state. */
|
||||
ANTFS_STATE_TRANS /**< Transport state. */
|
||||
} antfs_state_t;
|
||||
|
||||
// ANT-FS link layer substates.
|
||||
typedef enum
|
||||
{
|
||||
ANTFS_LINK_SUBSTATE_NONE /**< None state. */
|
||||
} antfs_link_substate_t;
|
||||
|
||||
// ANT-FS authenticate layer substates. */
|
||||
typedef enum
|
||||
{
|
||||
ANTFS_AUTH_SUBSTATE_NONE, /**< None state. */
|
||||
ANTFS_AUTH_SUBSTATE_PAIR, /**< Pairing state. */
|
||||
ANTFS_AUTH_SUBSTATE_PASSKEY, /**< Passkey state. */
|
||||
ANTFS_AUTH_SUBSTATE_ACCEPT, /**< Authenticate accept state. */
|
||||
ANTFS_AUTH_SUBSTATE_REJECT /**< Authenticate reject state. */
|
||||
} antfs_authenticate_substate_t;
|
||||
|
||||
// ANT-FS transport layer substates. */
|
||||
typedef enum
|
||||
{
|
||||
ANTFS_TRANS_SUBSTATE_NONE, /**< None state. */
|
||||
ANTFS_TRANS_SUBSTATE_VERIFY_CRC, /**< Verify CRC state. */
|
||||
ANTFS_TRANS_SUBSTATE_DOWNLOADING, /**< Downloading state. */
|
||||
ANTFS_TRANS_SUBSTATE_UPLOAD_WAIT_FOR_DATA, /**< Wait for upload data request state. */
|
||||
ANTFS_TRANS_SUBSTATE_UPLOADING, /**< Ready / receiving upload data state. */
|
||||
ANTFS_TRANS_SUBSTATE_UPLOAD_RESUME /**< RX failure upon receiving upload data state. */
|
||||
} antfs_transport_substate_t;
|
||||
|
||||
// ANT-FS Events.
|
||||
typedef enum
|
||||
{
|
||||
ANTFS_EVENT_PAIRING_REQUEST = 0xB0, /**< Pairing request event. */
|
||||
ANTFS_EVENT_PAIRING_TIMEOUT = 0xB1, /**< Pairing timeout event. */
|
||||
ANTFS_EVENT_OPEN_COMPLETE = 0xB2, /**< Channel setup complete event. */
|
||||
ANTFS_EVENT_CLOSE_COMPLETE = 0xB4, /**< Channel closed event. */
|
||||
ANTFS_EVENT_LINK = 0xB6, /**< Enter link layer event. */
|
||||
ANTFS_EVENT_AUTH = 0xB7, /**< Enter authenticate layer event. */
|
||||
ANTFS_EVENT_TRANS = 0xB8, /**< Enter transport layer event. */
|
||||
ANTFS_EVENT_DOWNLOAD_REQUEST = 0xB9, /**< Download request event. */
|
||||
ANTFS_EVENT_DOWNLOAD_REQUEST_DATA = 0xBA, /**< Download request data event. */
|
||||
ANTFS_EVENT_DOWNLOAD_START = 0xBB, /**< Download started event. */
|
||||
ANTFS_EVENT_DOWNLOAD_COMPLETE = 0xBC, /**< Download completed event. */
|
||||
ANTFS_EVENT_DOWNLOAD_FAIL = 0xBD, /**< Download failed event. */
|
||||
ANTFS_EVENT_UPLOAD_REQUEST = 0xBE, /**< Upload request event. */
|
||||
ANTFS_EVENT_UPLOAD_DATA = 0xBF, /**< Upload data available for read event. */
|
||||
ANTFS_EVENT_UPLOAD_START = 0xC0, /**< Upload begin event. */
|
||||
ANTFS_EVENT_UPLOAD_COMPLETE = 0xC1, /**< Upload completed event. */
|
||||
ANTFS_EVENT_UPLOAD_FAIL = 0xC2, /**< Upload process failed event. */
|
||||
ANTFS_EVENT_ERASE_REQUEST = 0xC3 /**< Erase request event. */
|
||||
} antfs_event_t;
|
||||
|
||||
/**@brief ANT-FS <-> application event communication object. */
|
||||
typedef struct
|
||||
{
|
||||
antfs_event_t event; /**< ANT-FS event. */
|
||||
uint16_t file_index; /**< File index (download/upload/erase). */
|
||||
uint32_t offset; /**< Current offset (download/upload). */
|
||||
uint32_t bytes; /**< Number of bytes in block (download/upload). */
|
||||
uint16_t crc; /**< Current CRC (upload). */
|
||||
uint8_t data[8]; /**< Block of data (upload). */
|
||||
} antfs_event_return_t;
|
||||
|
||||
/**@brief ANT-FS parameters. */
|
||||
typedef struct
|
||||
{
|
||||
uint32_t client_serial_number; /**< Client serial number. */
|
||||
uint16_t beacon_device_type; /**< Client device type. */
|
||||
uint16_t beacon_device_manufacturing_id; /**< Client manufacturing ID. */
|
||||
uint8_t beacon_frequency; /**< Beacon RF Frequency. */
|
||||
antfs_beacon_status_byte1_t beacon_status_byte1; /**< Beacon status byte 1. */
|
||||
const uint8_t * p_pass_key; /**< Pass Key. */
|
||||
const uint8_t * p_remote_friendly_name; /**< Friendly Name. */
|
||||
} antfs_params_t;
|
||||
|
||||
/**@brief ANT-FS directory header. */
|
||||
typedef struct
|
||||
{
|
||||
uint8_t version; /**< Version of the directory file structure. */
|
||||
uint8_t length; /**< Length of each structure, in bytes. */
|
||||
uint8_t time_format; /**< Defines how system keeps track of date/time stamps. */
|
||||
uint8_t reserved01;
|
||||
uint8_t reserved02;
|
||||
uint8_t reserved03;
|
||||
uint8_t reserved04;
|
||||
uint8_t reserved05;
|
||||
uint32_t system_time; /**< Number of seconds elapsed since system power up. */
|
||||
uint32_t date; /**< Number of seconds elapsed since 00:00 hrs Dec 31, 1989. If system time is unknown, used as counter. */
|
||||
} antfs_dir_header_t;
|
||||
|
||||
/**@brief ANT-FS directory entry. */
|
||||
typedef struct
|
||||
{
|
||||
uint16_t data_file_index; /**< Data file index. */
|
||||
uint8_t file_data_type; /**< File data type. */
|
||||
uint8_t user_defined1; /**< Identifier, first byte (structure defined by data type). */
|
||||
uint16_t user_defined2; /**< Identifier, last two bytes (structure defined by data type). */
|
||||
uint8_t user_flags; /**< File data type specific flags (bits defined by data type). */
|
||||
uint8_t general_flags; /**< Bit mapped flags of flag permissions. */
|
||||
uint32_t file_size_in_bytes; /**< File size, in bytes. */
|
||||
uint32_t date; /**< Number of seconds elapsed since 00:00 hrs Dec 31, 1980, if supported. */
|
||||
} antfs_dir_struct_t;
|
||||
|
||||
/**@brief ANT-FS download/upload request context. */
|
||||
typedef struct
|
||||
{
|
||||
ulong_union_t file_size; /**< Size of a file to download when reading, or the size of a partially completed upload when writing. */
|
||||
uint32_t max_file_size; /**< The maximum size of the file specified, this is the file size when reading, and the maximum allowed file size when writing. */
|
||||
ulong_union_t max_burst_block_size; /**< Maximum burst block size. */
|
||||
ushort_union_t file_index; /**< File index. */
|
||||
uint16_t file_crc; /**< CRC (uploads). */
|
||||
} antfs_request_info_t;
|
||||
|
||||
/**@brief The burst wait handler can be configured by the application to customize the code that is
|
||||
* executed while waiting for the burst busy flag. */
|
||||
typedef void(*antfs_burst_wait_handler_t)(void);
|
||||
|
||||
/**@brief Function for setting initial ANT-FS configuration parameters.
|
||||
*
|
||||
* @param[in] p_params The initial ANT-FS configuration parameters.
|
||||
* @param[in] burst_wait_handler Burst wait handler.
|
||||
*/
|
||||
void antfs_init(const antfs_params_t * const p_params,
|
||||
antfs_burst_wait_handler_t burst_wait_handler);
|
||||
|
||||
/**@brief Function for getting host name if received.
|
||||
*
|
||||
* @return Pointer to host name buffer if a host name was recieved, NULL otherwise.
|
||||
*/
|
||||
const char * antfs_hostname_get(void);
|
||||
|
||||
/**@brief Function for transmitting a response to a pairing request issued by ANT-FS host.
|
||||
*
|
||||
* @param[in] accept The pairing response, true if pairing accepted.
|
||||
*
|
||||
* @retval true Operation success. Response to a pairing request was transmitted.
|
||||
* @retval false Operation failure. Not in pairing mode or pairing not supported by the
|
||||
* implementation.
|
||||
*/
|
||||
bool antfs_pairing_resp_transmit(bool accept);
|
||||
|
||||
/**@brief Function for doing calculations prior downloading the data to the ANT-FS host.
|
||||
*
|
||||
* Function does the necessary pre processing calculations, which are required prior downloading the
|
||||
* data, and also transmits the download request response right away in case of the download request
|
||||
* was rejected or there is no data to send.
|
||||
*
|
||||
* @param[in] response The download request response code.
|
||||
* @param[in] p_request_info ANT-FS request info structure.
|
||||
*/
|
||||
void antfs_download_req_resp_prepare(uint8_t response,
|
||||
const antfs_request_info_t * const p_request_info);
|
||||
|
||||
/**@brief Function for downloading requested data.
|
||||
*
|
||||
* @param[in] index Index of the current file downloaded.
|
||||
* @param[in] offset Offset specified by client.
|
||||
* @param[in] num_bytes Number of bytes requested to be transmitted from the buffer.
|
||||
* @param[in] p_message Data buffer to be transmitted.
|
||||
*
|
||||
* @return Number of data bytes transmitted.
|
||||
*/
|
||||
uint32_t antfs_input_data_download(uint16_t index,
|
||||
uint32_t offset,
|
||||
uint32_t num_bytes,
|
||||
const uint8_t * const p_message);
|
||||
|
||||
/**@brief Function for transmitting upload request response to a upload request command by ANT-FS
|
||||
* host.
|
||||
*
|
||||
* @param[in] response The upload response code.
|
||||
* @param[in] p_request_info ANT-FS request info structure.
|
||||
*
|
||||
* @retval true Operation success. Response to upload request command was transmitted.
|
||||
* @retval false Operation failure. Upload not supported by the implementation or not in correct
|
||||
* state or application is sending a response for a different file
|
||||
* than requested.
|
||||
*/
|
||||
bool antfs_upload_req_resp_transmit(uint8_t response,
|
||||
const antfs_request_info_t * const p_request_info);
|
||||
|
||||
/**@brief Function for transmitting upload data response to a upload data command by ANT-FS host.
|
||||
*
|
||||
* @param[in] data_upload_success The upload response code, true for success.
|
||||
*
|
||||
* @retval true Operation success. Response to upload data command was transmitted.
|
||||
* @retval false Operation failure. Upload not supported by the implementation or not in correct
|
||||
* state.
|
||||
*/
|
||||
bool antfs_upload_data_resp_transmit(bool data_upload_success);
|
||||
|
||||
/**@brief Function for transmitting erase response to a erase request.
|
||||
*
|
||||
* @param[in] response The erase response code.
|
||||
*/
|
||||
void antfs_erase_req_resp_transmit(uint8_t response);
|
||||
|
||||
/**@brief Function for extracting possible pending ANT-FS event.
|
||||
*
|
||||
* @param[out] p_event The output event structure.
|
||||
*
|
||||
* @retval true Operation success. Pending ANT-FS event available and it was copied to the output
|
||||
* event structure.
|
||||
* @retval false Operation failure. No pending ANT-FS event available.
|
||||
*/
|
||||
bool antfs_event_extract(antfs_event_return_t * const p_event);
|
||||
|
||||
/**@brief Function for processing ANT events and data received from the ANT-FS channel.
|
||||
*
|
||||
* @param[in] p_message The message buffer containing the message received from the ANT-FS
|
||||
* channel.
|
||||
*/
|
||||
void antfs_message_process(uint8_t * p_message);
|
||||
|
||||
/**@brief Function for setting up the ANT-FS channel.
|
||||
*/
|
||||
void antfs_channel_setup(void);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // ANTFS_H__
|
||||
|
||||
/**
|
||||
*@}
|
||||
**/
|
|
@ -0,0 +1,100 @@
|
|||
/**
|
||||
* This software is subject to the ANT+ Shared Source License
|
||||
* www.thisisant.com/swlicenses
|
||||
* Copyright (c) Garmin Canada 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 Garmin 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;
|
||||
}
|
|
@ -0,0 +1,97 @@
|
|||
/**
|
||||
* This software is subject to the ANT+ Shared Source License
|
||||
* www.thisisant.com/swlicenses
|
||||
* Copyright (c) Garmin Canada 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 Garmin 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 in August 2012 by Garmin Canada Inc.
|
||||
* (former Dynastream Innovations Inc.)
|
||||
* @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__
|
||||
|
||||
/**
|
||||
*@}
|
||||
**/
|
|
@ -0,0 +1,112 @@
|
|||
/**
|
||||
* This software is subject to the ANT+ Shared Source License
|
||||
* www.thisisant.com/swlicenses
|
||||
* Copyright (c) Garmin Canada 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 Garmin 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 in August 2012 by Garmin Canada Inc.
|
||||
* (former Dynastream Innovations Inc.)
|
||||
* @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__
|
||||
|
||||
/**
|
||||
*@}
|
||||
**/
|
|
@ -0,0 +1,67 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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)
|
|
@ -0,0 +1,104 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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__
|
|
@ -0,0 +1,69 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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__
|
|
@ -0,0 +1,490 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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_BPWR)
|
||||
|
||||
#include "nrf_assert.h"
|
||||
#include "app_error.h"
|
||||
#include "ant_interface.h"
|
||||
#include "ant_bpwr.h"
|
||||
|
||||
#define NRF_LOG_MODULE_NAME ant_bpwr
|
||||
#if ANT_BPWR_LOG_ENABLED
|
||||
#define NRF_LOG_LEVEL ANT_BPWR_LOG_LEVEL
|
||||
#define NRF_LOG_INFO_COLOR ANT_BPWR_INFO_COLOR
|
||||
#else // ANT_BPWR_LOG_ENABLED
|
||||
#define NRF_LOG_LEVEL 0
|
||||
#endif // ANT_BPWR_LOG_ENABLED
|
||||
#include "nrf_log.h"
|
||||
NRF_LOG_MODULE_REGISTER();
|
||||
|
||||
#define BPWR_CALIB_INT_TIMEOUT ((ANT_CLOCK_FREQUENCY * BPWR_CALIBRATION_TIMOUT_S) / BPWR_MSG_PERIOD) // calibration timeout in ant message period's unit
|
||||
|
||||
// for torque sensor Minimum: Interleave every 9th message
|
||||
#define BPWR_PAGE_16_INTERVAL 5 // Preferred: Interleave every 5th message
|
||||
#define BPWR_PAGE_16_INTERVAL_OFS 2 // Permissible offset
|
||||
#define COMMON_PAGE_80_INTERVAL 119 // Minimum: Interleave every 121 messages
|
||||
#define COMMON_PAGE_81_INTERVAL 120 // Minimum: Interleave every 121 messages
|
||||
#define AUTO_ZERO_SUPPORT_INTERVAL 120 // Minimum: Interleave every 121 messages
|
||||
|
||||
/**@brief Bicycle power message data layout structure. */
|
||||
typedef struct
|
||||
{
|
||||
uint8_t page_number;
|
||||
uint8_t page_payload[7];
|
||||
} ant_bpwr_message_layout_t;
|
||||
|
||||
|
||||
/**@brief Function for initializing the ANT Bicycle Power Profile instance.
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
* @param[in] p_channel_config Pointer to the ANT channel configuration structure.
|
||||
*
|
||||
* @retval NRF_SUCCESS If initialization was successful. Otherwise, an error code is returned.
|
||||
*/
|
||||
static ret_code_t ant_bpwr_init(ant_bpwr_profile_t * p_profile,
|
||||
ant_channel_config_t const * p_channel_config)
|
||||
{
|
||||
p_profile->channel_number = p_channel_config->channel_number;
|
||||
|
||||
p_profile->page_1 = DEFAULT_ANT_BPWR_PAGE1();
|
||||
p_profile->page_16 = DEFAULT_ANT_BPWR_PAGE16();
|
||||
p_profile->page_17 = DEFAULT_ANT_BPWR_PAGE17();
|
||||
p_profile->page_18 = DEFAULT_ANT_BPWR_PAGE18();
|
||||
p_profile->page_80 = DEFAULT_ANT_COMMON_page80();
|
||||
p_profile->page_81 = DEFAULT_ANT_COMMON_page81();
|
||||
|
||||
NRF_LOG_INFO("ANT B-PWR channel %u init", p_profile->channel_number);
|
||||
return ant_channel_init(p_channel_config);
|
||||
}
|
||||
|
||||
|
||||
ret_code_t ant_bpwr_disp_init(ant_bpwr_profile_t * p_profile,
|
||||
ant_channel_config_t const * p_channel_config,
|
||||
ant_bpwr_disp_config_t const * p_disp_config)
|
||||
{
|
||||
ASSERT(p_profile != NULL);
|
||||
ASSERT(p_channel_config != NULL);
|
||||
ASSERT(p_disp_config != NULL);
|
||||
ASSERT(p_disp_config->evt_handler != NULL);
|
||||
ASSERT(p_disp_config->p_cb != NULL);
|
||||
|
||||
p_profile->evt_handler = p_disp_config->evt_handler;
|
||||
p_profile->_cb.p_disp_cb = p_disp_config->p_cb;
|
||||
|
||||
p_profile->_cb.p_disp_cb ->calib_timeout = 0;
|
||||
p_profile->_cb.p_disp_cb ->calib_stat = BPWR_DISP_CALIB_NONE;
|
||||
|
||||
return ant_bpwr_init(p_profile, p_channel_config);
|
||||
}
|
||||
|
||||
|
||||
ret_code_t ant_bpwr_sens_init(ant_bpwr_profile_t * p_profile,
|
||||
ant_channel_config_t const * p_channel_config,
|
||||
ant_bpwr_sens_config_t const * p_sens_config)
|
||||
{
|
||||
ASSERT(p_profile != NULL);
|
||||
ASSERT(p_channel_config != NULL);
|
||||
ASSERT(p_sens_config != NULL);
|
||||
ASSERT(p_sens_config->p_cb != NULL);
|
||||
ASSERT(p_sens_config->evt_handler != NULL);
|
||||
ASSERT(p_sens_config->calib_handler != NULL);
|
||||
|
||||
p_profile->evt_handler = p_sens_config->evt_handler;
|
||||
p_profile->_cb.p_sens_cb = p_sens_config->p_cb;
|
||||
|
||||
p_profile->_cb.p_sens_cb->torque_use = p_sens_config->torque_use;
|
||||
p_profile->_cb.p_sens_cb->calib_handler = p_sens_config->calib_handler;
|
||||
p_profile->_cb.p_sens_cb->calib_stat = BPWR_SENS_CALIB_NONE;
|
||||
p_profile->_cb.p_sens_cb->message_counter = 0;
|
||||
|
||||
return ant_bpwr_init(p_profile, p_channel_config);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/**@brief Function for getting next page number to send.
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
*
|
||||
* @return Next page number.
|
||||
*/
|
||||
static ant_bpwr_page_t next_page_number_get(ant_bpwr_profile_t * p_profile)
|
||||
{
|
||||
ant_bpwr_sens_cb_t * p_bpwr_cb = p_profile->_cb.p_sens_cb;
|
||||
ant_bpwr_page_t page_number;
|
||||
|
||||
if (p_bpwr_cb->calib_stat == BPWR_SENS_CALIB_READY)
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_1;
|
||||
p_bpwr_cb->calib_stat = BPWR_SENS_CALIB_NONE; // mark event as processed
|
||||
}
|
||||
else if ((p_profile->BPWR_PROFILE_auto_zero_status != ANT_BPWR_AUTO_ZERO_NOT_SUPPORTED)
|
||||
&& (p_bpwr_cb->message_counter == AUTO_ZERO_SUPPORT_INTERVAL))
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_1;
|
||||
p_profile->BPWR_PROFILE_calibration_id = ANT_BPWR_CALIB_ID_AUTO_SUPPORT;
|
||||
p_bpwr_cb->message_counter++;
|
||||
}
|
||||
else if (p_bpwr_cb->message_counter >= COMMON_PAGE_81_INTERVAL)
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_81;
|
||||
p_bpwr_cb->message_counter = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (p_bpwr_cb->message_counter == COMMON_PAGE_80_INTERVAL)
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_80;
|
||||
}
|
||||
else
|
||||
{
|
||||
if ( p_bpwr_cb->torque_use == TORQUE_NONE)
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_16;
|
||||
}
|
||||
else if ((p_bpwr_cb->message_counter % BPWR_PAGE_16_INTERVAL)
|
||||
== BPWR_PAGE_16_INTERVAL_OFS)
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_16;
|
||||
}
|
||||
else if ( p_bpwr_cb->torque_use == TORQUE_WHEEL)
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_17;
|
||||
}
|
||||
else // assumed TORQUE_CRANK
|
||||
{
|
||||
page_number = ANT_BPWR_PAGE_18;
|
||||
}
|
||||
}
|
||||
p_bpwr_cb->message_counter++;
|
||||
}
|
||||
|
||||
return page_number;
|
||||
}
|
||||
|
||||
|
||||
/**@brief Function for encoding Bicycle Power Sensor message.
|
||||
*
|
||||
* @note Assume to be call each time when Tx window will occur.
|
||||
*/
|
||||
static void sens_message_encode(ant_bpwr_profile_t * p_profile, uint8_t * p_message_payload)
|
||||
{
|
||||
ant_bpwr_message_layout_t * p_bpwr_message_payload =
|
||||
(ant_bpwr_message_layout_t *)p_message_payload;
|
||||
|
||||
p_bpwr_message_payload->page_number = next_page_number_get(p_profile);
|
||||
|
||||
NRF_LOG_INFO("B-PWR tx page: %u", p_bpwr_message_payload->page_number);
|
||||
|
||||
switch (p_bpwr_message_payload->page_number)
|
||||
{
|
||||
case ANT_BPWR_PAGE_1:
|
||||
ant_bpwr_page_1_encode(p_bpwr_message_payload->page_payload, &(p_profile->page_1));
|
||||
break;
|
||||
|
||||
case ANT_BPWR_PAGE_16:
|
||||
ant_bpwr_page_16_encode(p_bpwr_message_payload->page_payload, &(p_profile->page_16));
|
||||
ant_bpwr_cadence_encode(p_bpwr_message_payload->page_payload, &(p_profile->common));
|
||||
break;
|
||||
|
||||
case ANT_BPWR_PAGE_17:
|
||||
ant_bpwr_page_17_encode(p_bpwr_message_payload->page_payload, &(p_profile->page_17));
|
||||
ant_bpwr_cadence_encode(p_bpwr_message_payload->page_payload, &(p_profile->common));
|
||||
break;
|
||||
|
||||
case ANT_BPWR_PAGE_18:
|
||||
ant_bpwr_page_18_encode(p_bpwr_message_payload->page_payload, &(p_profile->page_18));
|
||||
ant_bpwr_cadence_encode(p_bpwr_message_payload->page_payload, &(p_profile->common));
|
||||
break;
|
||||
|
||||
case ANT_COMMON_PAGE_80:
|
||||
ant_common_page_80_encode(p_bpwr_message_payload->page_payload, &(p_profile->page_80));
|
||||
break;
|
||||
|
||||
case ANT_COMMON_PAGE_81:
|
||||
ant_common_page_81_encode(p_bpwr_message_payload->page_payload, &(p_profile->page_81));
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
p_profile->evt_handler(p_profile, (ant_bpwr_evt_t)p_bpwr_message_payload->page_number);
|
||||
|
||||
}
|
||||
|
||||
|
||||
/**@brief Function for decoding messages received by Bicycle Power sensor message.
|
||||
*
|
||||
* @note Assume to be call each time when Rx window will occur.
|
||||
*/
|
||||
static void sens_message_decode(ant_bpwr_profile_t * p_profile, uint8_t * p_message_payload)
|
||||
{
|
||||
const ant_bpwr_message_layout_t * p_bpwr_message_payload =
|
||||
(ant_bpwr_message_layout_t *)p_message_payload;
|
||||
ant_bpwr_page1_data_t page1;
|
||||
|
||||
switch (p_bpwr_message_payload->page_number)
|
||||
{
|
||||
case ANT_BPWR_PAGE_1:
|
||||
ant_bpwr_page_1_decode(p_bpwr_message_payload->page_payload, &page1);
|
||||
p_profile->_cb.p_sens_cb->calib_stat = BPWR_SENS_CALIB_REQUESTED;
|
||||
p_profile->_cb.p_sens_cb->calib_handler(p_profile, &page1);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**@brief Function for decoding messages received by Bicycle Power display message.
|
||||
*
|
||||
* @note Assume to be call each time when Rx window will occur.
|
||||
*/
|
||||
static void disp_message_decode(ant_bpwr_profile_t * p_profile, uint8_t * p_message_payload)
|
||||
{
|
||||
const ant_bpwr_message_layout_t * p_bpwr_message_payload =
|
||||
(ant_bpwr_message_layout_t *)p_message_payload;
|
||||
|
||||
NRF_LOG_INFO("B-PWR rx page: %u", p_bpwr_message_payload->page_number);
|
||||
|
||||
switch (p_bpwr_message_payload->page_number)
|
||||
{
|
||||
case ANT_BPWR_PAGE_1:
|
||||
ant_bpwr_page_1_decode(p_bpwr_message_payload->page_payload, &(p_profile->page_1));
|
||||
p_profile->_cb.p_disp_cb->calib_stat = BPWR_DISP_CALIB_NONE;
|
||||
break;
|
||||
|
||||
case ANT_BPWR_PAGE_16:
|
||||
ant_bpwr_page_16_decode(p_bpwr_message_payload->page_payload, &(p_profile->page_16));
|
||||
ant_bpwr_cadence_decode(p_bpwr_message_payload->page_payload, &(p_profile->common));
|
||||
break;
|
||||
|
||||
case ANT_BPWR_PAGE_17:
|
||||
ant_bpwr_page_17_decode(p_bpwr_message_payload->page_payload, &(p_profile->page_17));
|
||||
ant_bpwr_cadence_decode(p_bpwr_message_payload->page_payload, &(p_profile->common));
|
||||
break;
|
||||
|
||||
case ANT_BPWR_PAGE_18:
|
||||
ant_bpwr_page_18_decode(p_bpwr_message_payload->page_payload, &(p_profile->page_18));
|
||||
ant_bpwr_cadence_decode(p_bpwr_message_payload->page_payload, &(p_profile->common));
|
||||
break;
|
||||
|
||||
case ANT_COMMON_PAGE_80:
|
||||
ant_common_page_80_decode(p_bpwr_message_payload->page_payload, &(p_profile->page_80));
|
||||
break;
|
||||
|
||||
case ANT_COMMON_PAGE_81:
|
||||
ant_common_page_81_decode(p_bpwr_message_payload->page_payload, &(p_profile->page_81));
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
p_profile->evt_handler(p_profile, (ant_bpwr_evt_t)p_bpwr_message_payload->page_number);
|
||||
}
|
||||
|
||||
|
||||
ret_code_t ant_bpwr_calib_request(ant_bpwr_profile_t * p_profile, ant_bpwr_page1_data_t * p_page_1)
|
||||
{
|
||||
ant_bpwr_message_layout_t bpwr_message_payload;
|
||||
|
||||
if (p_profile->_cb.p_disp_cb->calib_stat == BPWR_DISP_CALIB_REQUESTED)
|
||||
{
|
||||
return NRF_SUCCESS; // calibration in progress, so omit this request
|
||||
}
|
||||
|
||||
bpwr_message_payload.page_number = ANT_BPWR_PAGE_1;
|
||||
ant_bpwr_page_1_encode(bpwr_message_payload.page_payload, p_page_1);
|
||||
|
||||
uint32_t err_code = sd_ant_acknowledge_message_tx(p_profile->channel_number,
|
||||
sizeof (bpwr_message_payload),
|
||||
(uint8_t *) &bpwr_message_payload);
|
||||
|
||||
if (err_code == NRF_SUCCESS)
|
||||
{
|
||||
p_profile->_cb.p_disp_cb->calib_timeout = BPWR_CALIB_INT_TIMEOUT; // initialize watch on calibration's time-out
|
||||
p_profile->_cb.p_disp_cb->calib_stat = BPWR_DISP_CALIB_REQUESTED;
|
||||
NRF_LOG_INFO("Start calibration process");
|
||||
}
|
||||
return err_code;
|
||||
}
|
||||
|
||||
|
||||
void ant_bpwr_calib_response(ant_bpwr_profile_t * p_profile)
|
||||
{
|
||||
if (p_profile->_cb.p_sens_cb->calib_stat != BPWR_SENS_CALIB_READY) // abort if callback request is in progress
|
||||
{
|
||||
p_profile->_cb.p_sens_cb->calib_stat = BPWR_SENS_CALIB_READY; // calibration respond
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**@brief Function for hangling calibration events.
|
||||
*/
|
||||
static void service_calib(ant_bpwr_profile_t * p_profile, uint8_t event)
|
||||
{
|
||||
ant_bpwr_evt_t bpwr_event;
|
||||
|
||||
if (p_profile->_cb.p_disp_cb->calib_stat == BPWR_DISP_CALIB_REQUESTED)
|
||||
{
|
||||
switch (event)
|
||||
{
|
||||
case EVENT_RX:
|
||||
/* fall through */
|
||||
case EVENT_RX_FAIL:
|
||||
|
||||
if (p_profile->_cb.p_disp_cb->calib_timeout-- == 0)
|
||||
{
|
||||
bpwr_event = ANT_BPWR_CALIB_TIMEOUT;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
case EVENT_TRANSFER_TX_FAILED:
|
||||
bpwr_event = ANT_BPWR_CALIB_REQUEST_TX_FAILED;
|
||||
break;
|
||||
|
||||
case EVENT_RX_SEARCH_TIMEOUT:
|
||||
bpwr_event = ANT_BPWR_CALIB_TIMEOUT;
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
NRF_LOG_INFO("End calibration process");
|
||||
p_profile->_cb.p_disp_cb->calib_stat = BPWR_DISP_CALIB_NONE;
|
||||
|
||||
p_profile->evt_handler(p_profile, bpwr_event);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static void ant_message_send(ant_bpwr_profile_t * p_profile)
|
||||
{
|
||||
uint32_t err_code;
|
||||
uint8_t p_message_payload[ANT_STANDARD_DATA_PAYLOAD_SIZE];
|
||||
|
||||
sens_message_encode(p_profile, p_message_payload);
|
||||
err_code =
|
||||
sd_ant_broadcast_message_tx(p_profile->channel_number,
|
||||
sizeof (p_message_payload),
|
||||
p_message_payload);
|
||||
APP_ERROR_CHECK(err_code);
|
||||
}
|
||||
|
||||
|
||||
ret_code_t ant_bpwr_disp_open(ant_bpwr_profile_t * p_profile)
|
||||
{
|
||||
NRF_LOG_INFO("ANT B-PWR %u open", p_profile->channel_number);
|
||||
return sd_ant_channel_open(p_profile->channel_number);
|
||||
}
|
||||
|
||||
|
||||
ret_code_t ant_bpwr_sens_open(ant_bpwr_profile_t * p_profile)
|
||||
{
|
||||
// Fill tx buffer for the first frame
|
||||
ant_message_send(p_profile);
|
||||
|
||||
NRF_LOG_INFO("ANT B-PWR %u open", p_profile->channel_number);
|
||||
return sd_ant_channel_open(p_profile->channel_number);
|
||||
}
|
||||
|
||||
|
||||
void ant_bpwr_sens_evt_handler(ant_evt_t * p_ant_event, void * p_context)
|
||||
{
|
||||
ant_bpwr_profile_t * p_profile = ( ant_bpwr_profile_t *)p_context;
|
||||
|
||||
if (p_ant_event->channel == p_profile->channel_number)
|
||||
{
|
||||
switch (p_ant_event->event)
|
||||
{
|
||||
case EVENT_TX:
|
||||
ant_message_send(p_profile);
|
||||
break;
|
||||
|
||||
case EVENT_RX:
|
||||
if (p_ant_event->message.ANT_MESSAGE_ucMesgID == MESG_ACKNOWLEDGED_DATA_ID)
|
||||
{
|
||||
sens_message_decode(p_profile, p_ant_event->message.ANT_MESSAGE_aucPayload);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
// No implementation needed
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void ant_bpwr_disp_evt_handler(ant_evt_t * p_ant_event, void * p_context)
|
||||
{
|
||||
ant_bpwr_profile_t * p_profile = ( ant_bpwr_profile_t *)p_context;
|
||||
|
||||
if (p_ant_event->channel == p_profile->channel_number)
|
||||
{
|
||||
switch (p_ant_event->event)
|
||||
{
|
||||
case EVENT_RX:
|
||||
|
||||
if (p_ant_event->message.ANT_MESSAGE_ucMesgID == MESG_BROADCAST_DATA_ID
|
||||
|| p_ant_event->message.ANT_MESSAGE_ucMesgID == MESG_ACKNOWLEDGED_DATA_ID
|
||||
|| p_ant_event->message.ANT_MESSAGE_ucMesgID == MESG_BURST_DATA_ID)
|
||||
{
|
||||
disp_message_decode(p_profile, p_ant_event->message.ANT_MESSAGE_aucPayload);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
service_calib(p_profile, p_ant_event->event);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // NRF_MODULE_ENABLED(ANT_BPWR)
|
|
@ -0,0 +1,377 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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.
|
||||
*
|
||||
*/
|
||||
/**
|
||||
* @file
|
||||
* @defgroup ant_bpwr Bicycle Power profile
|
||||
* @{
|
||||
* @ingroup ant_sdk_profiles
|
||||
* @brief This module implements the Bicycle Power profile.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef ANT_BICYCLE_POWER_H__
|
||||
#define ANT_BICYCLE_POWER_H__
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "ant_parameters.h"
|
||||
#include "nrf_sdh_ant.h"
|
||||
#include "ant_channel_config.h"
|
||||
#include "ant_bpwr_pages.h"
|
||||
#include "sdk_errors.h"
|
||||
|
||||
#define BPWR_DEVICE_TYPE 0x0Bu ///< Device type reserved for ANT+ Bicycle Power.
|
||||
#define BPWR_ANTPLUS_RF_FREQ 0x39u ///< Frequency, decimal 57 (2457 MHz).
|
||||
#define BPWR_MSG_PERIOD 8182u ///< Message period, decimal 8182 (4.0049 Hz).
|
||||
|
||||
#define BPWR_EXT_ASSIGN 0x00 ///< ANT ext assign (see Ext. Assign Channel Parameters in ant_parameters.h: @ref ant_parameters).
|
||||
#define BPWR_DISP_CHANNEL_TYPE CHANNEL_TYPE_SLAVE ///< Display Bicycle Power channel type.
|
||||
#define BPWR_SENS_CHANNEL_TYPE CHANNEL_TYPE_MASTER ///< Sensor Bicycle Power channel type.
|
||||
|
||||
#define BPWR_CALIBRATION_TIMOUT_S 5u ///< Time-out for responding to calibration callback (s).
|
||||
|
||||
|
||||
/**@brief Initialize an ANT channel configuration structure for the Bicycle Power profile (Display).
|
||||
*
|
||||
* @param[in] NAME Name of related instance.
|
||||
* @param[in] CHANNEL_NUMBER Number of the channel assigned to the profile instance.
|
||||
* @param[in] TRANSMISSION_TYPE Type of transmission assigned to the profile instance.
|
||||
* @param[in] DEVICE_NUMBER Number of the device assigned to the profile instance.
|
||||
* @param[in] NETWORK_NUMBER Number of the network assigned to the profile instance.
|
||||
*/
|
||||
#define BPWR_DISP_CHANNEL_CONFIG_DEF(NAME, \
|
||||
CHANNEL_NUMBER, \
|
||||
TRANSMISSION_TYPE, \
|
||||
DEVICE_NUMBER, \
|
||||
NETWORK_NUMBER) \
|
||||
static const ant_channel_config_t CONCAT_2(NAME, _channel_bpwr_disp_config) = \
|
||||
{ \
|
||||
.channel_number = (CHANNEL_NUMBER), \
|
||||
.channel_type = BPWR_DISP_CHANNEL_TYPE, \
|
||||
.ext_assign = BPWR_EXT_ASSIGN, \
|
||||
.rf_freq = BPWR_ANTPLUS_RF_FREQ, \
|
||||
.transmission_type = (TRANSMISSION_TYPE), \
|
||||
.device_type = BPWR_DEVICE_TYPE, \
|
||||
.device_number = (DEVICE_NUMBER), \
|
||||
.channel_period = BPWR_MSG_PERIOD, \
|
||||
.network_number = (NETWORK_NUMBER), \
|
||||
}
|
||||
#define BPWR_DISP_CHANNEL_CONFIG(NAME) &CONCAT_2(NAME, _channel_bpwr_disp_config)
|
||||
|
||||
/**@brief Initialize an ANT channel configuration structure for the Bicycle Power profile (Sensor).
|
||||
*
|
||||
* @param[in] NAME Name of related instance.
|
||||
* @param[in] CHANNEL_NUMBER Number of the channel assigned to the profile instance.
|
||||
* @param[in] TRANSMISSION_TYPE Type of transmission assigned to the profile instance.
|
||||
* @param[in] DEVICE_NUMBER Number of the device assigned to the profile instance.
|
||||
* @param[in] NETWORK_NUMBER Number of the network assigned to the profile instance.
|
||||
*/
|
||||
#define BPWR_SENS_CHANNEL_CONFIG_DEF(NAME, \
|
||||
CHANNEL_NUMBER, \
|
||||
TRANSMISSION_TYPE, \
|
||||
DEVICE_NUMBER, \
|
||||
NETWORK_NUMBER) \
|
||||
static const ant_channel_config_t CONCAT_2(NAME, _channel_bpwr_sens_config) = \
|
||||
{ \
|
||||
.channel_number = (CHANNEL_NUMBER), \
|
||||
.channel_type = BPWR_SENS_CHANNEL_TYPE, \
|
||||
.ext_assign = BPWR_EXT_ASSIGN, \
|
||||
.rf_freq = BPWR_ANTPLUS_RF_FREQ, \
|
||||
.transmission_type = (TRANSMISSION_TYPE), \
|
||||
.device_type = BPWR_DEVICE_TYPE, \
|
||||
.device_number = (DEVICE_NUMBER), \
|
||||
.channel_period = BPWR_MSG_PERIOD, \
|
||||
.network_number = (NETWORK_NUMBER), \
|
||||
}
|
||||
#define BPWR_SENS_CHANNEL_CONFIG(NAME) &CONCAT_2(NAME, _channel_bpwr_sens_config)
|
||||
|
||||
/**@brief Initialize an ANT profile configuration structure for the BPWR profile (Display).
|
||||
*
|
||||
* @param[in] NAME Name of related instance.
|
||||
* @param[in] EVT_HANDLER Event handler to be called for handling events in the BPWR profile.
|
||||
*/
|
||||
#define BPWR_DISP_PROFILE_CONFIG_DEF(NAME, \
|
||||
EVT_HANDLER) \
|
||||
static ant_bpwr_disp_cb_t CONCAT_2(NAME, _bpwr_disp_cb); \
|
||||
static const ant_bpwr_disp_config_t CONCAT_2(NAME, _profile_bpwr_disp_config) = \
|
||||
{ \
|
||||
.p_cb = &CONCAT_2(NAME, _bpwr_disp_cb), \
|
||||
.evt_handler = (EVT_HANDLER), \
|
||||
}
|
||||
#define BPWR_DISP_PROFILE_CONFIG(NAME) &CONCAT_2(NAME, _profile_bpwr_disp_config)
|
||||
|
||||
|
||||
/**@brief Initialize an ANT profile configuration structure for the BPWR profile (Sensor).
|
||||
*
|
||||
* @param[in] NAME Name of related instance.
|
||||
* @param[in] TORQUE_USED Determines whether the torque page is included.
|
||||
* @param[in] CALIB_HANDLER Event handler to be called for handling calibration requests.
|
||||
* @param[in] EVT_HANDLER Event handler to be called for handling events in the BPWR profile.
|
||||
*/
|
||||
#define BPWR_SENS_PROFILE_CONFIG_DEF(NAME, \
|
||||
TORQUE_USED, \
|
||||
CALIB_HANDLER, \
|
||||
EVT_HANDLER) \
|
||||
static ant_bpwr_sens_cb_t CONCAT_2(NAME, _bpwr_sens_cb); \
|
||||
static const ant_bpwr_sens_config_t CONCAT_2(NAME, _profile_bpwr_sens_config) = \
|
||||
{ \
|
||||
.torque_use = (TORQUE_USED), \
|
||||
.calib_handler = (CALIB_HANDLER), \
|
||||
.p_cb = &CONCAT_2(NAME, _bpwr_sens_cb), \
|
||||
.evt_handler = (EVT_HANDLER), \
|
||||
}
|
||||
#define BPWR_SENS_PROFILE_CONFIG(NAME) &NAME##_profile_bpwr_sens_config
|
||||
|
||||
|
||||
/**@brief Configuration values for the Bicycle Power torque page. */
|
||||
typedef enum
|
||||
{
|
||||
TORQUE_NONE = 0,
|
||||
TORQUE_WHEEL = 1,
|
||||
TORQUE_CRANK = 2,
|
||||
} ant_bpwr_torque_t;
|
||||
|
||||
/**@brief Bicycle Power page number type. */
|
||||
typedef enum
|
||||
{
|
||||
ANT_BPWR_PAGE_1 = 1, ///< Calibration data page.
|
||||
ANT_BPWR_PAGE_16 = 16, ///< Standard power-only main data page.
|
||||
ANT_BPWR_PAGE_17 = 17, ///< Standard wheel torque main data page.
|
||||
ANT_BPWR_PAGE_18 = 18, ///< Standard crank torque main data page.
|
||||
ANT_BPWR_PAGE_80 = ANT_COMMON_PAGE_80,
|
||||
ANT_BPWR_PAGE_81 = ANT_COMMON_PAGE_81
|
||||
} ant_bpwr_page_t;
|
||||
|
||||
/**@brief BPWR profile event type. */
|
||||
typedef enum
|
||||
{
|
||||
ANT_BPWR_PAGE_1_UPDATED = ANT_BPWR_PAGE_1, ///< Data page 1 and speed have been updated (Display) or sent (Sensor).
|
||||
ANT_BPWR_PAGE_16_UPDATED = ANT_BPWR_PAGE_16, ///< Data page 16 and speed have been updated (Display) or sent (Sensor).
|
||||
ANT_BPWR_PAGE_17_UPDATED = ANT_BPWR_PAGE_17, ///< Data page 17 and speed have been updated (Display) or sent (Sensor).
|
||||
ANT_BPWR_PAGE_18_UPDATED = ANT_BPWR_PAGE_18, ///< Data page 18 has been updated (Display) or sent (Sensor).
|
||||
ANT_BPWR_PAGE_80_UPDATED = ANT_BPWR_PAGE_80, ///< Data page 80 has been updated (Display) or sent (Sensor).
|
||||
ANT_BPWR_PAGE_81_UPDATED = ANT_BPWR_PAGE_81, ///< Data page 81 has been updated (Display) or sent (Sensor).
|
||||
ANT_BPWR_CALIB_TIMEOUT, ///< Request of calibration time-out occurred (Display).
|
||||
ANT_BPWR_CALIB_REQUEST_TX_FAILED, ///< Calibration request did not reach the destination (Display).
|
||||
} ant_bpwr_evt_t;
|
||||
|
||||
// Forward declaration of the ant_bpwr_profile_t type.
|
||||
typedef struct ant_bpwr_profile_s ant_bpwr_profile_t;
|
||||
|
||||
/**@brief BPWR event handler type. */
|
||||
typedef void (* ant_bpwr_evt_handler_t) (ant_bpwr_profile_t *, ant_bpwr_evt_t);
|
||||
|
||||
/**@brief BPWR Sensor calibration request handler type. */
|
||||
typedef void (* ant_bpwr_calib_handler_t) (ant_bpwr_profile_t *, ant_bpwr_page1_data_t *);
|
||||
|
||||
#include "ant_bpwr_local.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**@brief Bicycle Power Sensor configuration structure. */
|
||||
typedef struct
|
||||
{
|
||||
ant_bpwr_torque_t torque_use; ///< Determines whether the torque page is included.
|
||||
ant_bpwr_sens_cb_t * p_cb; ///< Pointer to the data buffer for internal use.
|
||||
ant_bpwr_evt_handler_t evt_handler; ///< Event handler to be called for handling events in the BPWR profile.
|
||||
ant_bpwr_calib_handler_t calib_handler; ///< Event handler to be called for handling calibration requests.
|
||||
} ant_bpwr_sens_config_t;
|
||||
|
||||
/**@brief Bicycle Power Display configuration structure. */
|
||||
typedef struct
|
||||
{
|
||||
ant_bpwr_disp_cb_t * p_cb; ///< Pointer to the data buffer for internal use.
|
||||
ant_bpwr_evt_handler_t evt_handler; ///< Event handler to be called for handling events in the BPWR profile.
|
||||
} ant_bpwr_disp_config_t;
|
||||
|
||||
/**@brief Bicycle Power profile structure. */
|
||||
struct ant_bpwr_profile_s
|
||||
{
|
||||
uint8_t channel_number; ///< Channel number assigned to the profile.
|
||||
union {
|
||||
ant_bpwr_disp_cb_t * p_disp_cb;
|
||||
ant_bpwr_sens_cb_t * p_sens_cb;
|
||||
} _cb; ///< Pointer to internal control block.
|
||||
ant_bpwr_evt_handler_t evt_handler; ///< Event handler to be called for handling events in the BPWR profile.
|
||||
ant_bpwr_page1_data_t page_1; ///< Page 1.
|
||||
ant_bpwr_page16_data_t page_16; ///< Page 16.
|
||||
ant_bpwr_page17_data_t page_17; ///< Page 17.
|
||||
ant_bpwr_page18_data_t page_18; ///< Page 18.
|
||||
ant_common_page80_data_t page_80; ///< Page 80.
|
||||
ant_common_page81_data_t page_81; ///< Page 81.
|
||||
ant_bpwr_common_data_t common; ///< BPWR common data.
|
||||
};
|
||||
|
||||
/** @name Defines for accessing ant_bpwr_profile_t member variables
|
||||
@{ */
|
||||
#define BPWR_PROFILE_calibration_id page_1.calibration_id
|
||||
#define BPWR_PROFILE_auto_zero_status page_1.auto_zero_status
|
||||
#define BPWR_PROFILE_general_calib_data page_1.data.general_calib
|
||||
#define BPWR_PROFILE_custom_calib_data page_1.data.custom_calib
|
||||
#define BPWR_PROFILE_instantaneous_cadence common.instantaneous_cadence
|
||||
#define BPWR_PROFILE_pedal_power page_16.pedal_power.items
|
||||
#define BPWR_PROFILE_power_update_event_count page_16.update_event_count
|
||||
#define BPWR_PROFILE_accumulated_power page_16.accumulated_power
|
||||
#define BPWR_PROFILE_instantaneous_power page_16.instantaneous_power
|
||||
#define BPWR_PROFILE_wheel_update_event_count page_17.update_event_count
|
||||
#define BPWR_PROFILE_wheel_tick page_17.tick
|
||||
#define BPWR_PROFILE_wheel_period page_17.period
|
||||
#define BPWR_PROFILE_wheel_accumulated_torque page_17.accumulated_torque
|
||||
#define BPWR_PROFILE_crank_update_event_count page_18.update_event_count
|
||||
#define BPWR_PROFILE_crank_tick page_18.tick
|
||||
#define BPWR_PROFILE_crank_period page_18.period
|
||||
#define BPWR_PROFILE_crank_accumulated_torque page_18.accumulated_torque
|
||||
#define BPWR_PROFILE_manuf_id page_80.manuf_id
|
||||
#define BPWR_PROFILE_hw_revision page_80.hw_revision
|
||||
#define BPWR_PROFILE_manufacturer_id page_80.manufacturer_id
|
||||
#define BPWR_PROFILE_model_number page_80.model_number
|
||||
#define BPWR_PROFILE_sw_revision_minor page_81.sw_revision_minor
|
||||
#define BPWR_PROFILE_sw_revision_major page_81.sw_revision_major
|
||||
#define BPWR_PROFILE_serial_number page_81.serial_number
|
||||
/** @} */
|
||||
|
||||
/**@brief Function for initializing the ANT Bicycle Power Display profile instance.
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
* @param[in] p_channel_config Pointer to the ANT channel configuration structure.
|
||||
* @param[in] p_disp_config Pointer to the Bicycle Power Display configuration structure.
|
||||
*
|
||||
* @retval NRF_SUCCESS If initialization was successful. Otherwise, an error code is returned.
|
||||
*/
|
||||
ret_code_t ant_bpwr_disp_init(ant_bpwr_profile_t * p_profile,
|
||||
ant_channel_config_t const * p_channel_config,
|
||||
ant_bpwr_disp_config_t const * p_disp_config);
|
||||
|
||||
/**@brief Function for initializing the ANT Bicycle Power Sensor profile instance.
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
* @param[in] p_channel_config Pointer to the ANT channel configuration structure.
|
||||
* @param[in] p_sens_config Pointer to the Bicycle Power Sensor configuration structure.
|
||||
*
|
||||
* @retval NRF_SUCCESS If initialization was successful. Otherwise, an error code is returned.
|
||||
*/
|
||||
ret_code_t ant_bpwr_sens_init(ant_bpwr_profile_t * p_profile,
|
||||
ant_channel_config_t const * p_channel_config,
|
||||
ant_bpwr_sens_config_t const * p_sens_config);
|
||||
|
||||
/**@brief Function for opening the profile instance channel for ANT BPWR Display.
|
||||
*
|
||||
* Before calling this function, pages should be configured.
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
*
|
||||
* @retval NRF_SUCCESS If the channel was successfully opened. Otherwise, an error code is returned.
|
||||
*/
|
||||
ret_code_t ant_bpwr_disp_open(ant_bpwr_profile_t * p_profile);
|
||||
|
||||
/**@brief Function for opening the profile instance channel for ANT BPWR Sensor.
|
||||
*
|
||||
* Before calling this function, pages should be configured.
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
*
|
||||
* @retval NRF_SUCCESS If the channel was successfully opened. Otherwise, an error code is returned.
|
||||
*/
|
||||
ret_code_t ant_bpwr_sens_open(ant_bpwr_profile_t * p_profile);
|
||||
|
||||
/** @name Functions: Sensor calibration API
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @brief Function for initializing the response for a calibration request.
|
||||
*
|
||||
* This function should be used to signal the status of the calibration procedure to the ANT profile layer .
|
||||
*
|
||||
* @param[in] p_profile Pointer to the profile instance.
|
||||
*/
|
||||
void ant_bpwr_calib_response(ant_bpwr_profile_t * p_profile);
|
||||
/** @} */
|
||||
|
||||
|
||||
/**@brief Function for handling the Sensor ANT events.
|
||||
*
|
||||
* @details This function handles all events from the ANT stack that are of interest to the Bicycle Power Display profile.
|
||||
*
|
||||
* @param[in] p_ant_evt Event received from the ANT stack.
|
||||
* @param[in] p_context Pointer to the profile instance.
|
||||
*/
|
||||
void ant_bpwr_sens_evt_handler(ant_evt_t * p_ant_evt, void * p_context);
|
||||
|
||||
/**@brief Function for handling the Display ANT events.
|
||||
*
|
||||
* @details This function handles all events from the ANT stack that are of interest to the Bicycle Power Display profile.
|
||||
*
|
||||
* @param[in] p_ant_evt Event received from the ANT stack.
|
||||
* @param[in] p_context Pointer to the profile instance.
|
||||
*/
|
||||
void ant_bpwr_disp_evt_handler(ant_evt_t * p_ant_evt, void * p_context);
|
||||
|
||||
/** @name Functions: Display calibration API
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**@brief Function for initializing the calibration request process from the Bicycle Power Display side.
|
||||
*
|
||||
* @details This function requests a transfer to the Sensor and starts watching for the calibration response.
|
||||
* If a calibration response has already been requested, the function ignores the new request and returns NRF_SUCCESS.
|
||||
*
|
||||
* @param [in] p_profile Pointer to the profile instance.
|
||||
* @param [in] p_page_1 Pointer to the prepared page 1.
|
||||
*
|
||||
* @return Values returned by the @ref sd_ant_acknowledge_message_tx SVC callback.
|
||||
*/
|
||||
uint32_t ant_bpwr_calib_request(ant_bpwr_profile_t * p_profile, ant_bpwr_page1_data_t * p_page_1);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // ANT_BICYCLE_POWER_H__
|
||||
|
|
@ -0,0 +1,89 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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__
|
|
@ -0,0 +1,99 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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_BPWR)
|
||||
|
||||
#include "ant_bpwr_common_data.h"
|
||||
#include "ant_bpwr_utils.h"
|
||||
|
||||
#define NRF_LOG_MODULE_NAME ant_bpwr_common
|
||||
#if ANT_BPWR_COMMON_LOG_ENABLED
|
||||
#define NRF_LOG_LEVEL ANT_BPWR_COMMON_LOG_LEVEL
|
||||
#define NRF_LOG_INFO_COLOR ANT_BPWR_COMMON_INFO_COLOR
|
||||
#else // ANT_BPWR_COMMON_LOG_ENABLED
|
||||
#define NRF_LOG_LEVEL 0
|
||||
#endif // ANT_BPWR_COMMON_LOG_ENABLED
|
||||
#include "nrf_log.h"
|
||||
NRF_LOG_MODULE_REGISTER();
|
||||
|
||||
/**@brief BPWR common page data layout structure. */
|
||||
typedef struct
|
||||
{
|
||||
uint8_t reserved0[2];
|
||||
uint8_t instantaneous_cadence;
|
||||
uint8_t reserved1[4];
|
||||
}ant_bpwr_cadence_data_layout_t;
|
||||
|
||||
/**@brief Function for tracing common data.
|
||||
*
|
||||
* @param[in] p_common_data Pointer to the common data.
|
||||
*/
|
||||
static void cadence_data_log(ant_bpwr_common_data_t const * p_common_data)
|
||||
{
|
||||
if (p_common_data->instantaneous_cadence == 0xFF)
|
||||
{
|
||||
NRF_LOG_INFO("instantaneous cadence: -- rpm\r\n\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
NRF_LOG_INFO("instantaneous cadence: %u rpm\r\n\n",
|
||||
p_common_data->instantaneous_cadence);
|
||||
}
|
||||
}
|
||||
|
||||
void ant_bpwr_cadence_encode(uint8_t * p_page_buffer,
|
||||
ant_bpwr_common_data_t const * p_common_data)
|
||||
{
|
||||
ant_bpwr_cadence_data_layout_t * p_outcoming_data = (ant_bpwr_cadence_data_layout_t *)p_page_buffer;
|
||||
p_outcoming_data->instantaneous_cadence = p_common_data->instantaneous_cadence;
|
||||
|
||||
cadence_data_log(p_common_data);
|
||||
}
|
||||
|
||||
void ant_bpwr_cadence_decode(uint8_t const * p_page_buffer,
|
||||
ant_bpwr_common_data_t * p_common_data)
|
||||
{
|
||||
ant_bpwr_cadence_data_layout_t const * p_incoming_data = (ant_bpwr_cadence_data_layout_t *)p_page_buffer;
|
||||
p_common_data->instantaneous_cadence = p_incoming_data->instantaneous_cadence;
|
||||
|
||||
cadence_data_log(p_common_data);
|
||||
}
|
||||
|
||||
#endif // NRF_MODULE_ENABLED(ANT_BPWR)
|
|
@ -0,0 +1,99 @@
|
|||
/**
|
||||
* Copyright (c) 2015 - 2019, 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_COMMON_DATA_H__
|
||||
#define ANT_BPWR_COMMON_DATA_H__
|
||||
|
||||
/** @file
|
||||
*
|
||||
* @defgroup ant_sdk_profiles_bpwr_common_data_page Stride Based Speed and Distance Monitor profile common data
|
||||
* @{
|
||||
* @ingroup ant_sdk_profiles_bpwr_pages
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**@brief Data structure for BPWR common data.
|
||||
*
|
||||
* @details This structure stores data that is not associated with a particular page.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t instantaneous_cadence; ///< Crank cadence (rpm, 0 - 254, 255-> invalid).
|
||||
} ant_bpwr_common_data_t;
|
||||
|
||||
/**@brief Initialize common data.
|
||||
*/
|
||||
#define DEFAULT_ANT_BPWR_COMMON_DATA() \
|
||||
(ant_bpwr_common_data_t) \
|
||||
{ \
|
||||
.instantaneous_cadence = 0, \
|
||||
}
|
||||
|
||||
/**@brief Function for encoding speed.
|
||||
*
|
||||
* This function can be used for pages 16, 17, and 18.
|
||||
*
|
||||
* @param[in] p_common_data Pointer to the common data.
|
||||
* @param[out] p_page_buffer Pointer to the data buffer.
|
||||
*/
|
||||
void ant_bpwr_cadence_encode(uint8_t * p_page_buffer,
|
||||
ant_bpwr_common_data_t const * p_common_data);
|
||||
|
||||
/**@brief Function for decoding speed.
|
||||
*
|
||||
* This function can be used for pages 16, 17, and 18.
|
||||
*
|
||||
* @param[in] p_page_buffer Pointer to the data buffer.
|
||||
* @param[out] p_common_data Pointer to the common data.
|
||||
*/
|
||||
void ant_bpwr_cadence_decode(uint8_t const * p_page_buffer,
|
||||
ant_bpwr_common_data_t * p_common_data);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // ANT_BPWR_COMMON_DATA_H__
|
||||
/** @} */
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue