ext: hal: Make Nordic HALs a Zephyr module

Moved to an external repo,
https://github.com/zephyrproject-rtos/hal_nordic.

Signed-off-by: Carles Cufi <carles.cufi@nordicsemi.no>
This commit is contained in:
Carles Cufi 2019-08-15 17:17:01 +02:00 committed by Anas Nashif
commit cf3af6af5f
266 changed files with 3 additions and 407544 deletions

View file

@ -207,7 +207,6 @@
/dts/bindings/sensor/st* @avisconti
/ext/hal/cmsis/ @MaureenHelm @galak
/ext/hal/microchip/ @franciscomunoz @albertofloyd @scottwcpg
/ext/hal/nordic/ @carlescufi @anangl
/ext/hal/nxp/ @MaureenHelm
/ext/lib/crypto/tinycrypt/ @ceolin
/include/ @nashif @carlescufi @galak @MaureenHelm

View file

@ -1,5 +1,4 @@
add_subdirectory(cmsis)
add_subdirectory(nordic)
add_subdirectory(nxp)
add_subdirectory(openisa)
add_subdirectory_ifdef(CONFIG_HAS_ALTERA_HAL altera)

View file

@ -16,8 +16,6 @@ source "ext/hal/cmsis/Kconfig"
source "ext/hal/microchip/Kconfig"
source "ext/hal/nordic/Kconfig"
source "ext/hal/nxp/mcux/Kconfig"
source "ext/hal/nxp/imx/Kconfig"

View file

@ -1,56 +0,0 @@
if(CONFIG_HAS_NORDIC_DRIVERS)
add_subdirectory(drivers)
endif()
if(CONFIG_HAS_NRFX)
zephyr_include_directories(nrfx)
zephyr_include_directories(nrfx/drivers/include)
zephyr_include_directories(nrfx/hal)
zephyr_include_directories(nrfx/mdk)
zephyr_include_directories(.)
# Define MDK defines globally
zephyr_compile_definitions_ifdef(CONFIG_SOC_SERIES_NRF51X NRF51)
zephyr_compile_definitions_ifdef(CONFIG_SOC_NRF52810 NRF52810_XXAA)
zephyr_compile_definitions_ifdef(CONFIG_SOC_NRF52811 NRF52811_XXAA)
zephyr_compile_definitions_ifdef(CONFIG_SOC_NRF52832 NRF52832_XXAA)
zephyr_compile_definitions_ifdef(CONFIG_SOC_NRF52840 NRF52840_XXAA)
zephyr_compile_definitions_ifdef(CONFIG_SOC_NRF9160 NRF9160_XXAA)
# Connect Kconfig compilation option for Non-Secure software with option required by MDK/nrfx
zephyr_compile_definitions_ifdef(CONFIG_ARM_NONSECURE_FIRMWARE NRF_TRUSTZONE_NONSECURE)
zephyr_sources_ifdef(CONFIG_SOC_SERIES_NRF51X nrfx/mdk/system_nrf51.c)
zephyr_sources_ifdef(CONFIG_SOC_NRF52810 nrfx/mdk/system_nrf52810.c)
zephyr_sources_ifdef(CONFIG_SOC_NRF52811 nrfx/mdk/system_nrf52811.c)
zephyr_sources_ifdef(CONFIG_SOC_NRF52832 nrfx/mdk/system_nrf52.c)
zephyr_sources_ifdef(CONFIG_SOC_NRF52840 nrfx/mdk/system_nrf52840.c)
zephyr_sources_ifdef(CONFIG_SOC_NRF9160 nrfx/mdk/system_nrf9160.c)
zephyr_sources(nrfx_glue.c)
zephyr_sources_ifdef(CONFIG_NRFX_PRS nrfx/drivers/prs/nrfx_prs.c)
zephyr_sources_ifdef(CONFIG_NRFX_ADC nrfx/drivers/src/nrfx_adc.c)
zephyr_sources_ifdef(CONFIG_NRFX_CLOCK nrfx/drivers/src/nrfx_clock.c)
zephyr_sources_ifdef(CONFIG_NRFX_DPPI nrfx/drivers/src/nrfx_dppi.c)
zephyr_sources_ifdef(CONFIG_NRFX_GPIOTE nrfx/drivers/src/nrfx_gpiote.c)
zephyr_sources_ifdef(CONFIG_NRFX_NFCT nrfx/drivers/src/nrfx_nfct.c)
zephyr_sources_ifdef(CONFIG_NRFX_NVMC nrfx/drivers/src/nrfx_nvmc.c)
zephyr_sources_ifdef(CONFIG_NRFX_PPI nrfx/drivers/src/nrfx_ppi.c)
zephyr_sources_ifdef(CONFIG_NRFX_PWM nrfx/drivers/src/nrfx_pwm.c)
zephyr_sources_ifdef(CONFIG_NRFX_QDEC nrfx/drivers/src/nrfx_qdec.c)
zephyr_sources_ifdef(CONFIG_NRFX_RTC nrfx/drivers/src/nrfx_rtc.c)
zephyr_sources_ifdef(CONFIG_NRFX_SAADC nrfx/drivers/src/nrfx_saadc.c)
zephyr_sources_ifdef(CONFIG_NRFX_SPI nrfx/drivers/src/nrfx_spi.c)
zephyr_sources_ifdef(CONFIG_NRFX_SPIM nrfx/drivers/src/nrfx_spim.c)
zephyr_sources_ifdef(CONFIG_NRFX_SPIS nrfx/drivers/src/nrfx_spis.c)
zephyr_sources_ifdef(CONFIG_NRFX_SYSTICK nrfx/drivers/src/nrfx_systick.c)
zephyr_sources_ifdef(CONFIG_NRFX_TIMER nrfx/drivers/src/nrfx_timer.c)
zephyr_sources_ifdef(CONFIG_NRFX_TWI nrfx/drivers/src/nrfx_twi.c)
zephyr_sources_ifdef(CONFIG_NRFX_TWIM nrfx/drivers/src/nrfx_twim.c)
zephyr_sources_ifdef(CONFIG_NRFX_UART nrfx/drivers/src/nrfx_uart.c)
zephyr_sources_ifdef(CONFIG_NRFX_UARTE nrfx/drivers/src/nrfx_uarte.c)
zephyr_sources_ifdef(CONFIG_NRFX_USBD nrfx/drivers/src/nrfx_usbd.c)
zephyr_sources_ifdef(CONFIG_NRFX_WDT nrfx/drivers/src/nrfx_wdt.c)
endif()

View file

@ -1,3 +0,0 @@
if(CONFIG_IEEE802154_NRF5)
add_subdirectory(nrf_radio_802154)
endif()

View file

@ -1,78 +0,0 @@
zephyr_include_directories(.)
zephyr_include_directories(rsch)
zephyr_include_directories(rsch/raal)
zephyr_sources(
nrf_802154_ack_pending_bit.c
nrf_802154_core_hooks.c
nrf_802154_core.c
nrf_802154_critical_section.c
nrf_802154_debug.c
nrf_802154_notification_direct.c
nrf_802154_pib.c
nrf_802154_priority_drop_direct.c
nrf_802154_request_direct.c
nrf_802154_revision.c
nrf_802154_rssi.c
nrf_802154_rx_buffer.c
nrf_802154_timer_coord.c
nrf_802154.c
mac_features/nrf_802154_filter.c
platform/clock/nrf_802154_clock_zephyr.c
platform/lp_timer/nrf_802154_lp_timer_zephyr.c
platform/temperature/nrf_802154_temperature_none.c
rsch/nrf_802154_rsch.c
rsch/nrf_802154_rsch_crit_sect.c
rsch/raal/single_phy/single_phy.c
timer_scheduler/nrf_802154_timer_sched.c
)
if( CONFIG_IEEE802154_NRF5_CCA_MODE_ED)
set(radio_cca_mode NRF_RADIO_CCA_MODE_ED)
elseif( CONFIG_IEEE802154_NRF5_CCA_MODE_CARRIER)
set(radio_cca_mode NRF_RADIO_CCA_MODE_CARRIER)
elseif( CONFIG_IEEE802154_NRF5_CCA_MODE_CARRIER_AND_ED)
set(radio_cca_mode NRF_RADIO_CCA_MODE_CARRIER_AND_ED)
elseif( CONFIG_IEEE802154_NRF5_CCA_MODE_CARRIER_OR_ED)
set(radio_cca_mode NRF_RADIO_CCA_MODE_CARRIER_OR_ED)
endif()
zephyr_compile_definitions(
# Until IRQ configuration abstraction is added to the radio driver do not set
# radio IRQ priority to 0, or the radio IRQ will ignore IRQ lock.
NRF_802154_IRQ_PRIORITY=1
NRF_802154_INTERNAL_RADIO_IRQ_HANDLING=0
# Radio driver shim layer uses raw api
NRF_802154_USE_RAW_API=1
# Number of slots containing short addresses of nodes for which
# pending data is stored.
NRF_802154_PENDING_SHORT_ADDRESSES=16
# Number of slots containing extended addresses of nodes for which
# pending data is stored.
NRF_802154_PENDING_EXTENDED_ADDRESSES=16
# Number of buffers in receive queue.
NRF_802154_RX_BUFFERS=8
# CCA mode
NRF_802154_CCA_MODE_DEFAULT=${radio_cca_mode}
# CCA mode options
NRF_802154_CCA_CORR_LIMIT_DEFAULT=${CONFIG_IEEE802154_NRF5_CCA_CORR_LIMIT}
NRF_802154_CCA_CORR_THRESHOLD_DEFAULT=${CONFIG_IEEE802154_NRF5_CCA_CORR_THRESHOLD}
NRF_802154_CCA_ED_THRESHOLD_DEFAULT=${CONFIG_IEEE802154_NRF5_CCA_ED_THRESHOLD}
# Disable unused radio driver features
NRF_802154_CSMA_CA_ENABLED=0
NRF_802154_ACK_TIMEOUT_ENABLED=0
NRF_802154_FRAME_TIMESTAMP_ENABLED=0
NRF_802154_DELAYED_TRX_ENABLED=0
NRF_802154_TX_STARTED_NOTIFY_ENABLED=0
)

View file

@ -1,30 +0,0 @@
BSD 3-Clause License
Copyright (c) 2010 - 2018, 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 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.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY, AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL 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.

View file

@ -1,17 +0,0 @@
# nRF IEEE 802.15.4 radio driver
[![Build Status][travis-svg]][travis]
[travis]: https://travis-ci.org/NordicSemiconductor/nRF-IEEE-802.15.4-radio-driver
[travis-svg]: https://travis-ci.org/NordicSemiconductor/nRF-IEEE-802.15.4-radio-driver.svg?branch=master
The nRF IEEE 802.15.4 radio driver implements the IEEE 802.15.4 PHY layer on the Nordic Semiconductor nRF52840 SoC.
The architecture of the nRF IEEE 802.15.4 radio driver is independent of the OS and IEEE 802.15.4 MAC layer.
It allows to use the driver in any IEEE 802.15.4 based stacks that implement protocols such as Thread, ZigBee, or RF4CE.
In addition, it was designed to work with multiprotocol applications. The driver allows to share the RADIO peripheral with other PHY protocol drivers, for example, Bluetooth LE.
For more information and a detailed description of the driver, see the [Wiki](https://github.com/NordicSemiconductor/nRF-IEEE-802.15.4-radio-driver/wiki).
Note that the *nRF-IEEE-802.15.4-radio-driver.packsc* file is a project building description used for internal testing in Nordic Semiconductor. This file is NOT needed to build the driver with any other tool.

View file

@ -1,370 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements common function for Front End Module control of the nRF 802.15.4 radio driver.
*
*/
#include "nrf_fem_control_api.h"
#include <assert.h>
#include "compiler_abstraction.h"
#include "nrf_fem_control_config.h"
#include "nrf_802154_config.h"
#include "nrf.h"
#include "hal/nrf_gpio.h"
#include "hal/nrf_gpiote.h"
#include "hal/nrf_ppi.h"
#include "hal/nrf_radio.h"
#include "hal/nrf_timer.h"
#define NRF_FEM_TIMER_INSTANCE NRF_802154_TIMER_INSTANCE
#if ENABLE_FEM
static nrf_fem_control_cfg_t m_nrf_fem_control_cfg; /**< FEM controller configuration. */
/** Check whether pin is valid and enabled. */
static bool pin_is_enabled(nrf_fem_control_pin_t pin)
{
switch (pin)
{
case NRF_FEM_CONTROL_LNA_PIN:
return m_nrf_fem_control_cfg.lna_cfg.enable;
case NRF_FEM_CONTROL_PA_PIN:
return m_nrf_fem_control_cfg.pa_cfg.enable;
case NRF_FEM_CONTROL_ANY_PIN:
return m_nrf_fem_control_cfg.lna_cfg.enable || m_nrf_fem_control_cfg.pa_cfg.enable;
default:
assert(false);
return false;
}
}
/**
* @section GPIO control.
*/
/** Initialize GPIO according to configuration provided. */
static void gpio_init(void)
{
if (m_nrf_fem_control_cfg.pa_cfg.enable)
{
nrf_gpio_cfg_output(m_nrf_fem_control_cfg.pa_cfg.gpio_pin);
nrf_gpio_pin_write(m_nrf_fem_control_cfg.pa_cfg.gpio_pin,
!m_nrf_fem_control_cfg.pa_cfg.active_high);
}
if (m_nrf_fem_control_cfg.lna_cfg.enable)
{
nrf_gpio_cfg_output(m_nrf_fem_control_cfg.lna_cfg.gpio_pin);
nrf_gpio_pin_write(m_nrf_fem_control_cfg.lna_cfg.gpio_pin,
!m_nrf_fem_control_cfg.lna_cfg.active_high);
}
}
/** Configure GPIOTE module. */
static void gpiote_configure(void)
{
nrf_gpiote_task_configure(m_nrf_fem_control_cfg.lna_gpiote_ch_id,
m_nrf_fem_control_cfg.lna_cfg.gpio_pin,
(nrf_gpiote_polarity_t)GPIOTE_CONFIG_POLARITY_None,
(nrf_gpiote_outinit_t) !m_nrf_fem_control_cfg.lna_cfg.active_high);
nrf_gpiote_task_enable(m_nrf_fem_control_cfg.lna_gpiote_ch_id);
nrf_gpiote_task_configure(m_nrf_fem_control_cfg.pa_gpiote_ch_id,
m_nrf_fem_control_cfg.pa_cfg.gpio_pin,
(nrf_gpiote_polarity_t)GPIOTE_CONFIG_POLARITY_None,
(nrf_gpiote_outinit_t) !m_nrf_fem_control_cfg.pa_cfg.active_high);
nrf_gpiote_task_enable(m_nrf_fem_control_cfg.pa_gpiote_ch_id);
}
/**
* @section PPI control.
*/
/** Initialize PPI according to configuration provided. */
static void ppi_init(void)
{
/* RADIO DISABLED --> clr LNA & clr PA PPI */
nrf_ppi_channel_and_fork_endpoint_setup(
(nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_clr,
(uint32_t)(&NRF_RADIO->EVENTS_DISABLED),
(m_nrf_fem_control_cfg.lna_cfg.active_high ?
(uint32_t)(&NRF_GPIOTE->TASKS_CLR[m_nrf_fem_control_cfg.lna_gpiote_ch_id]) :
(uint32_t)(&NRF_GPIOTE->TASKS_SET[m_nrf_fem_control_cfg.lna_gpiote_ch_id])),
(m_nrf_fem_control_cfg.pa_cfg.active_high ?
(uint32_t)(&NRF_GPIOTE->TASKS_CLR[m_nrf_fem_control_cfg.pa_gpiote_ch_id]) :
(uint32_t)(&NRF_GPIOTE->TASKS_SET[m_nrf_fem_control_cfg.pa_gpiote_ch_id])));
}
/** Setup PPI to set LNA pin on a timer event. */
static void ppi_lna_enable_setup(nrf_timer_cc_channel_t timer_cc_channel)
{
/* TIMER0->COMPARE --> set LNA PPI */
nrf_ppi_channel_endpoint_setup(
(nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_set,
(uint32_t)(&NRF_FEM_TIMER_INSTANCE->EVENTS_COMPARE[timer_cc_channel]),
(m_nrf_fem_control_cfg.lna_cfg.active_high ?
(uint32_t)(&NRF_GPIOTE->TASKS_SET[m_nrf_fem_control_cfg.lna_gpiote_ch_id]) :
(uint32_t)(&NRF_GPIOTE->TASKS_CLR[m_nrf_fem_control_cfg.lna_gpiote_ch_id])));
}
/** Setup PPI to set PA pin on a timer event. */
static void ppi_pa_enable_setup(nrf_timer_cc_channel_t timer_cc_channel)
{
/* TIMER2->COMPARE --> set PA PPI */
nrf_ppi_channel_endpoint_setup(
(nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_set,
(uint32_t)(&NRF_FEM_TIMER_INSTANCE->EVENTS_COMPARE[timer_cc_channel]),
(m_nrf_fem_control_cfg.pa_cfg.active_high ?
(uint32_t)(&NRF_GPIOTE->TASKS_SET[m_nrf_fem_control_cfg.pa_gpiote_ch_id]) :
(uint32_t)(&NRF_GPIOTE->TASKS_CLR[m_nrf_fem_control_cfg.pa_gpiote_ch_id])));
}
/**
* @section FEM API functions.
*/
void nrf_fem_control_cfg_set(const nrf_fem_control_cfg_t * p_cfg)
{
m_nrf_fem_control_cfg = *p_cfg;
if (m_nrf_fem_control_cfg.pa_cfg.enable || m_nrf_fem_control_cfg.lna_cfg.enable)
{
gpio_init();
gpiote_configure();
ppi_init();
nrf_ppi_channel_enable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_clr);
}
}
void nrf_fem_control_cfg_get(nrf_fem_control_cfg_t * p_cfg)
{
*p_cfg = m_nrf_fem_control_cfg;
}
void nrf_fem_control_activate(void)
{
if (m_nrf_fem_control_cfg.pa_cfg.enable || m_nrf_fem_control_cfg.lna_cfg.enable)
{
nrf_ppi_channel_enable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_clr);
}
}
void nrf_fem_control_deactivate(void)
{
if (m_nrf_fem_control_cfg.pa_cfg.enable || m_nrf_fem_control_cfg.lna_cfg.enable)
{
nrf_ppi_channel_disable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_clr);
nrf_ppi_channel_disable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_set);
}
}
void nrf_fem_control_ppi_enable(nrf_fem_control_pin_t pin, nrf_timer_cc_channel_t timer_cc_channel)
{
if (pin_is_enabled(pin))
{
switch (pin)
{
case NRF_FEM_CONTROL_LNA_PIN:
ppi_lna_enable_setup(timer_cc_channel);
nrf_ppi_channel_enable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_set);
break;
case NRF_FEM_CONTROL_PA_PIN:
ppi_pa_enable_setup(timer_cc_channel);
nrf_ppi_channel_enable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_set);
break;
default:
assert(false);
break;
}
}
}
void nrf_fem_control_ppi_disable(nrf_fem_control_pin_t pin)
{
if (pin_is_enabled(pin))
{
nrf_ppi_channel_disable((nrf_ppi_channel_t)m_nrf_fem_control_cfg.ppi_ch_id_set);
}
}
uint32_t nrf_fem_control_delay_get(nrf_fem_control_pin_t pin)
{
uint32_t target_time = 1;
if (pin_is_enabled(pin))
{
switch (pin)
{
case NRF_FEM_CONTROL_LNA_PIN:
target_time = NRF_FEM_RADIO_RX_STARTUP_LATENCY_US - NRF_FEM_LNA_TIME_IN_ADVANCE;
break;
case NRF_FEM_CONTROL_PA_PIN:
target_time = NRF_FEM_RADIO_TX_STARTUP_LATENCY_US - NRF_FEM_PA_TIME_IN_ADVANCE;
break;
default:
assert(false);
break;
}
}
return target_time;
}
void nrf_fem_control_pin_clear(void)
{
if (pin_is_enabled(NRF_FEM_CONTROL_PA_PIN))
{
nrf_gpiote_task_force(m_nrf_fem_control_cfg.pa_gpiote_ch_id,
(nrf_gpiote_outinit_t) !m_nrf_fem_control_cfg.pa_cfg.active_high);
}
if (pin_is_enabled(NRF_FEM_CONTROL_LNA_PIN))
{
nrf_gpiote_task_force(m_nrf_fem_control_cfg.lna_gpiote_ch_id,
(nrf_gpiote_outinit_t) !m_nrf_fem_control_cfg.lna_cfg.active_high);
}
}
void nrf_fem_control_timer_set(nrf_fem_control_pin_t pin,
nrf_timer_cc_channel_t timer_cc_channel,
nrf_timer_short_mask_t short_mask)
{
if (pin_is_enabled(pin))
{
uint32_t target_time = nrf_fem_control_delay_get(pin);
nrf_timer_shorts_enable(NRF_FEM_TIMER_INSTANCE, short_mask);
nrf_timer_cc_write(NRF_FEM_TIMER_INSTANCE, timer_cc_channel, target_time);
}
}
void nrf_fem_control_timer_reset(nrf_fem_control_pin_t pin, nrf_timer_short_mask_t short_mask)
{
if (pin_is_enabled(pin))
{
// Anomaly 78: use SHUTDOWN instead of STOP and CLEAR.
nrf_timer_task_trigger(NRF_FEM_TIMER_INSTANCE, NRF_TIMER_TASK_SHUTDOWN);
nrf_timer_shorts_disable(NRF_FEM_TIMER_INSTANCE, short_mask);
}
}
void nrf_fem_control_ppi_fork_setup(nrf_fem_control_pin_t pin,
nrf_ppi_channel_t ppi_channel,
uint32_t task_addr)
{
if (pin_is_enabled(pin))
{
nrf_ppi_fork_endpoint_setup(ppi_channel, task_addr);
}
}
void nrf_fem_control_ppi_task_setup(nrf_fem_control_pin_t pin,
nrf_ppi_channel_t ppi_channel,
uint32_t event_addr,
uint32_t task_addr)
{
if (pin_is_enabled(pin))
{
nrf_ppi_channel_endpoint_setup(ppi_channel, event_addr, task_addr);
nrf_ppi_channel_enable(ppi_channel);
}
}
void nrf_fem_control_ppi_fork_clear(nrf_fem_control_pin_t pin, nrf_ppi_channel_t ppi_channel)
{
if (pin_is_enabled(pin))
{
nrf_ppi_fork_endpoint_setup(ppi_channel, 0);
}
}
void nrf_fem_control_ppi_pin_task_setup(nrf_ppi_channel_t ppi_channel,
uint32_t event_addr,
bool lna_pin_set,
bool pa_pin_set)
{
uint32_t lna_task_addr = 0;
uint32_t pa_task_addr = 0;
if (m_nrf_fem_control_cfg.lna_cfg.enable)
{
if ((lna_pin_set && m_nrf_fem_control_cfg.lna_cfg.active_high) ||
(!lna_pin_set && !m_nrf_fem_control_cfg.lna_cfg.active_high))
{
lna_task_addr =
(uint32_t)(&NRF_GPIOTE->TASKS_SET[m_nrf_fem_control_cfg.lna_gpiote_ch_id]);
}
else
{
lna_task_addr =
(uint32_t)(&NRF_GPIOTE->TASKS_CLR[m_nrf_fem_control_cfg.lna_gpiote_ch_id]);
}
}
if (m_nrf_fem_control_cfg.pa_cfg.enable)
{
if ((pa_pin_set && m_nrf_fem_control_cfg.pa_cfg.active_high) ||
(!pa_pin_set && !m_nrf_fem_control_cfg.pa_cfg.active_high))
{
pa_task_addr =
(uint32_t)(&NRF_GPIOTE->TASKS_SET[m_nrf_fem_control_cfg.pa_gpiote_ch_id]);
}
else
{
pa_task_addr =
(uint32_t)(&NRF_GPIOTE->TASKS_CLR[m_nrf_fem_control_cfg.pa_gpiote_ch_id]);
}
}
if (lna_task_addr != 0 || pa_task_addr != 0)
{
nrf_ppi_channel_and_fork_endpoint_setup(ppi_channel, event_addr, lna_task_addr,
pa_task_addr);
nrf_ppi_channel_enable(ppi_channel);
}
}
#endif // ENABLE_FEM

View file

@ -1,261 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief Front End Module control for the nRF 802.15.4 radio driver.
*
*/
#ifndef NRF_FEM_CONTROL_API_H_
#define NRF_FEM_CONTROL_API_H_
#include <stdint.h>
#include <stdbool.h>
#include "hal/nrf_ppi.h"
#include "hal/nrf_timer.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @section Resource configuration.
*/
/** Default Power Amplifier pin. */
#define NRF_FEM_CONTROL_DEFAULT_PA_PIN 15
/** Default Low Noise Amplifier pin. */
#define NRF_FEM_CONTROL_DEFAULT_LNA_PIN 16
/** Default PPI channel for pin setting. */
#define NRF_FEM_CONTROL_DEFAULT_SET_PPI_CHANNEL 15
/** Default PPI channel for pin clearing. */
#define NRF_FEM_CONTROL_DEFAULT_CLR_PPI_CHANNEL 16
/** Default GPIOTE channel for FEM control. */
#define NRF_FEM_CONTROL_DEFAULT_LNA_GPIOTE_CHANNEL 6
/** Default GPIOTE channel for FEM control. */
#define NRF_FEM_CONTROL_DEFAULT_PA_GPIOTE_CHANNEL 7
#if ENABLE_FEM
/**
* @brief Configuration parameters for the PA and LNA.
*/
typedef struct
{
uint8_t enable : 1; /**< Enable toggling for this amplifier */
uint8_t active_high : 1; /**< Set the pin to be active high */
uint8_t gpio_pin : 6; /**< The GPIO pin to toggle for this amplifier */
} nrf_fem_control_pa_lna_cfg_t;
/**
* @brief PA & LNA GPIO toggle configuration
*
* This option configures the nRF 802.15.4 radio driver to toggle pins when the radio
* is active for use with a power amplifier and/or a low noise amplifier.
*
* Toggling the pins is achieved by using two PPI channels and a GPIOTE channel. The hardware channel IDs are provided
* by the application and should be regarded as reserved as long as any PA/LNA toggling is enabled.
*
* @note Changing this configuration while the radio is in use may have undefined
* consequences and must be avoided by the application.
*/
typedef struct
{
nrf_fem_control_pa_lna_cfg_t pa_cfg; /**< Power Amplifier configuration */
nrf_fem_control_pa_lna_cfg_t lna_cfg; /**< Low Noise Amplifier configuration */
uint8_t pa_gpiote_ch_id; /**< GPIOTE channel used for Power Amplifier pin toggling */
uint8_t lna_gpiote_ch_id; /**< GPIOTE channel used for Low Noise Amplifier pin toggling */
uint8_t ppi_ch_id_set; /**< PPI channel used for radio Power Amplifier and Low Noise Amplifier pins setting */
uint8_t ppi_ch_id_clr; /**< PPI channel used for radio pin clearing */
} nrf_fem_control_cfg_t;
/**
* @brief Hardware pins controlled by the Front End Module.
*/
typedef enum
{
NRF_FEM_CONTROL_PA_PIN,
NRF_FEM_CONTROL_LNA_PIN,
NRF_FEM_CONTROL_ANY_PIN,
} nrf_fem_control_pin_t;
/**@brief Set PA & LNA GPIO toggle configuration.
*
* @note This function shall not be called when radio is in use.
*
* @param[in] p_cfg A pointer to the PA & LNA GPIO toggle configuration.
*
*/
void nrf_fem_control_cfg_set(const nrf_fem_control_cfg_t * p_cfg);
/**@brief Get PA & LNA GPIO toggle configuration.
*
* @param[out] p_cfg A pointer to the structure for the PA & LNA GPIO toggle configuration.
*
*/
void nrf_fem_control_cfg_get(nrf_fem_control_cfg_t * p_cfg);
/**@brief Activate FEM controller.
*
* This function should be called when radio wakes up.
*/
void nrf_fem_control_activate(void);
/**@brief Deactivate FEM controller.
*
* This function should be called when radio goes to sleep.
*/
void nrf_fem_control_deactivate(void);
/**@brief Configure PPI to activate one of the Front End Module pins on an appropriate timer event.
*
* @param[in] pin The Front End Module controlled pin to be connected to the PPI.
* @param[in] timer_cc_channel Timer CC channel that triggers the @p pin activation through the PPI.
*
*/
void nrf_fem_control_ppi_enable(nrf_fem_control_pin_t pin, nrf_timer_cc_channel_t timer_cc_channel);
/**@brief Clear PPI configuration used to activate one of Front End Module pins.
*
* @param[in] pin The Front End Module controlled pin to be disconnected from the PPI.
*
*/
void nrf_fem_control_ppi_disable(nrf_fem_control_pin_t pin);
/**@brief Calculate target time for a timer, which activates one of the Front End Module pins.
*
* @param[in] pin The Front End Module controlled pin to be activated.
*
* @return @p pin activation delay in microseconds.
*
*/
uint32_t nrf_fem_control_delay_get(nrf_fem_control_pin_t pin);
/**@brief Clear the Power Amplifier and the Low Noise Amplifier pins immediately.
*
*/
void nrf_fem_control_pin_clear(void);
/**@brief Configure and set a timer for one of the Front End Module pins activation.
*
* @param[in] pin The Front End Module controlled pin to be activated.
* @param[in] timer_cc_channel Timer CC channel to set.
* @param[in] short_mask Mask of timer shortcuts to be enabled.
*
*/
void nrf_fem_control_timer_set(nrf_fem_control_pin_t pin,
nrf_timer_cc_channel_t timer_cc_channel,
nrf_timer_short_mask_t short_mask);
/**@brief Clear timer configuration after one of the Front End Module pins deactivation.
*
* @param[in] pin The Front End Module controlled pin that was deactivated.
* @param[in] short_mask Mask of timer shortcuts to be disabled.
*
*/
void nrf_fem_control_timer_reset(nrf_fem_control_pin_t pin, nrf_timer_short_mask_t short_mask);
/**@brief Setup a PPI fork task necessary for one of the Front End Module pins.
*
* @param[in] pin The Front End Module controlled pin that was deactivated.
* @param[in] ppi_channel PPI channel to connect the fork task to.
*
*/
void nrf_fem_control_ppi_fork_setup(nrf_fem_control_pin_t pin,
nrf_ppi_channel_t ppi_channel,
uint32_t task_addr);
/**@brief Setup a PPI task necessary for one of the Front End Module pins.
*
* @param[in] pin The Front End Module controlled pin that was deactivated.
* @param[in] ppi_channel PPI channel to connect the task to.
* @param[in] event_addr Address of the event to be connected to the PPI.
* @param[in] task_addr Address of the task to be connected to the PPI.
*
*/
void nrf_fem_control_ppi_task_setup(nrf_fem_control_pin_t pin,
nrf_ppi_channel_t ppi_channel,
uint32_t event_addr,
uint32_t task_addr);
/**@brief Clear a PPI fork task configuration for one of the Front End Module pins.
*
* @param[in] pin The Front End Module controlled pin that was deactivated.
* @param[in] ppi_channel PPI channel to disconnect the fork task from.
*
*/
void nrf_fem_control_ppi_fork_clear(nrf_fem_control_pin_t pin, nrf_ppi_channel_t ppi_channel);
/**@brief Setup PPI task and fork that set or clear Front End Module pins on a given event.
*
* @param[in] ppi_channel PPI channel to connect the task and fork to.
* @param[in] event_addr Address of the event to be connected to the PPI.
* @param[in] lna_pin_set If true, the Low Noise Amplifier pin will be set on the event @p event_addr.
* Otherwise, it will be cleared.
* @param[in] pa_pin_set If true, the Power Amplifier pin will be set on the event @p event_addr.
* Otherwise, it will be cleared.
*
*/
void nrf_fem_control_ppi_pin_task_setup(nrf_ppi_channel_t ppi_channel,
uint32_t event_addr,
bool lna_pin_set,
bool pa_pin_set);
#else // ENABLE_FEM
#define nrf_fem_control_cfg_set(...)
#define nrf_fem_control_cfg_get(...)
#define nrf_fem_control_activate(...)
#define nrf_fem_control_deactivate(...)
#define nrf_fem_control_ppi_enable(...)
#define nrf_fem_control_ppi_disable(...)
#define nrf_fem_control_delay_get(...) 1
#define nrf_fem_control_pin_clear(...)
#define nrf_fem_control_timer_set(...)
#define nrf_fem_control_timer_reset(...)
#define nrf_fem_control_ppi_fork_setup(...)
#define nrf_fem_control_ppi_task_setup(...)
#define nrf_fem_control_ppi_task_and_fork_setup(...)
#define nrf_fem_control_ppi_fork_clear(...)
#define nrf_fem_control_ppi_pin_task_setup(...)
#endif // ENABLE_FEM
#ifdef __cplusplus
}
#endif
#endif /* NRF_FEM_CONTROL_API_H_ */

View file

@ -1,66 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_FEM_CONTROL_CONFIG_H_
#define NRF_FEM_CONTROL_CONFIG_H_
#ifdef __cplusplus
extern "C" {
#endif
/**
* @section Timings.
*/
/** Time in us when PA GPIO is activated before radio is ready for transmission. */
#define NRF_FEM_PA_TIME_IN_ADVANCE 23
/** Time in us when LNA GPIO is activated before radio is ready for reception. */
#define NRF_FEM_LNA_TIME_IN_ADVANCE 5
#ifdef NRF52840_XXAA
/** Radio ramp-up time in TX mode, in us. */
#define NRF_FEM_RADIO_TX_STARTUP_LATENCY_US 40
/** Radio ramp-up time in RX mode, in us. */
#define NRF_FEM_RADIO_RX_STARTUP_LATENCY_US 40
#else
#error "Device not supported."
#endif
#ifdef __cplusplus
}
#endif
#endif /* NRF_FEM_CONTROL_CONFIG_H_ */

View file

@ -1,779 +0,0 @@
/* Copyright (c) 2016 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* @brief RADIO HAL API.
*/
#ifndef NRF_RADIO_H__
#define NRF_RADIO_H__
/**
* @defgroup nrf_radio_hal RADIO HAL
* @{
* @ingroup nrf_radio
* @brief Hardware access layer for managing the radio (RADIO).
*/
#include <stdint.h>
#include <stddef.h>
#include <stdbool.h>
#include "nrf.h"
#ifdef __cplusplus
extern "C" {
#endif
#define NRF_RADIO_TASK_SET (1UL)
#define NRF_RADIO_EVENT_CLEAR (0UL)
/**
* @enum nrf_radio_task_t
* @brief RADIO tasks.
*/
/*lint -save -e30 -esym(628,__INTADDR__) */
typedef enum
{
NRF_RADIO_TASK_TXEN = offsetof(NRF_RADIO_Type, TASKS_TXEN), /**< Enable radio transmitter. */
NRF_RADIO_TASK_RXEN = offsetof(NRF_RADIO_Type, TASKS_RXEN), /**< Enable radio receiver. */
NRF_RADIO_TASK_START = offsetof(NRF_RADIO_Type, TASKS_START), /**< Start radio transmission or reception. */
NRF_RADIO_TASK_STOP = offsetof(NRF_RADIO_Type, TASKS_STOP), /**< Stop radio transmission or reception. */
NRF_RADIO_TASK_DISABLE = offsetof(NRF_RADIO_Type, TASKS_DISABLE), /**< Disable radio transmitter and receiver. */
NRF_RADIO_TASK_CCASTART = offsetof(NRF_RADIO_Type, TASKS_CCASTART), /**< Start Clear Channel Assessment procedure. */
NRF_RADIO_TASK_CCASTOP = offsetof(NRF_RADIO_Type, TASKS_CCASTOP), /**< Stop Clear Channel Assessment procedure. */
NRF_RADIO_TASK_EDSTART = offsetof(NRF_RADIO_Type, TASKS_EDSTART), /**< Start Energy Detection procedure. */
NRF_RADIO_TASK_EDSTOP = offsetof(NRF_RADIO_Type, TASKS_EDSTOP), /**< Stop Energy Detection procedure. */
NRF_RADIO_TASK_RSSISTART = offsetof(NRF_RADIO_Type, TASKS_RSSISTART), /**< Start the RSSI and take one single sample of received signal strength. */
} nrf_radio_task_t;
/**
* @enum nrf_radio_event_t
* @brief RADIO events.
*/
typedef enum
{
NRF_RADIO_EVENT_READY = offsetof(NRF_RADIO_Type, EVENTS_READY), /**< Radio has ramped up and is ready to be started. */
NRF_RADIO_EVENT_ADDRESS = offsetof(NRF_RADIO_Type, EVENTS_ADDRESS), /**< Address sent or received. */
NRF_RADIO_EVENT_END = offsetof(NRF_RADIO_Type, EVENTS_END), /**< Packet transmitted or received. */
NRF_RADIO_EVENT_DISABLED = offsetof(NRF_RADIO_Type, EVENTS_DISABLED), /**< Radio has been disabled. */
NRF_RADIO_EVENT_RSSIEND = offsetof(NRF_RADIO_Type, EVENTS_RSSIEND), /**< Sampling of receive signal strength complete. */
NRF_RADIO_EVENT_BCMATCH = offsetof(NRF_RADIO_Type, EVENTS_BCMATCH), /**< Bit counter reached bit count value. */
NRF_RADIO_EVENT_CRCOK = offsetof(NRF_RADIO_Type, EVENTS_CRCOK), /**< Packet received with correct CRC. */
NRF_RADIO_EVENT_CRCERROR = offsetof(NRF_RADIO_Type, EVENTS_CRCERROR), /**< Packet received with incorrect CRC. */
NRF_RADIO_EVENT_FRAMESTART = offsetof(NRF_RADIO_Type, EVENTS_FRAMESTART), /**< IEEE 802.15.4 length field received. */
NRF_RADIO_EVENT_EDEND = offsetof(NRF_RADIO_Type, EVENTS_EDEND), /**< Energy Detection procedure ended. */
NRF_RADIO_EVENT_CCAIDLE = offsetof(NRF_RADIO_Type, EVENTS_CCAIDLE), /**< Wireless medium is idle. */
NRF_RADIO_EVENT_CCABUSY = offsetof(NRF_RADIO_Type, EVENTS_CCABUSY), /**< Wireless medium is busy. */
NRF_RADIO_EVENT_TXREADY = offsetof(NRF_RADIO_Type, EVENTS_TXREADY), /**< Radio has ramped up and is ready to be started TX path. */
NRF_RADIO_EVENT_RXREADY = offsetof(NRF_RADIO_Type, EVENTS_RXREADY), /**< Radio has ramped up and is ready to be started RX path. */
NRF_RADIO_EVENT_MHRMATCH = offsetof(NRF_RADIO_Type, EVENTS_MHRMATCH), /**< MAC Header match found. */
NRF_RADIO_EVENT_PHYEND = offsetof(NRF_RADIO_Type, EVENTS_PHYEND), /**< Generated in Ble_LR125Kbit, Ble_LR500Kbit and Ieee802154_250Kbit modes when last bit is sent on air. */
} nrf_radio_event_t;
/*lint -restore */
/**
* @enum nrf_radio_int_mask_t
* @brief RADIO interrupts.
*/
typedef enum
{
NRF_RADIO_INT_READY_MASK = RADIO_INTENSET_READY_Msk, /**< Mask for enabling or disabling an interrupt on READY event. */
NRF_RADIO_INT_ADDRESS_MASK = RADIO_INTENSET_ADDRESS_Msk, /**< Mask for enabling or disabling an interrupt on ADDRESS event. */
NRF_RADIO_INT_END_MASK = RADIO_INTENSET_END_Msk, /**< Mask for enabling or disabling an interrupt on END event. */
NRF_RADIO_INT_DISABLED_MASK = RADIO_INTENSET_DISABLED_Msk, /**< Mask for enabling or disabling an interrupt on DISABLED event. */
NRF_RADIO_INT_RSSIEND_MASK = RADIO_INTENSET_RSSIEND_Msk, /**< Mask for enabling or disabling an interrupt on RSSIEND event. */
NRF_RADIO_INT_BCMATCH_MASK = RADIO_INTENSET_BCMATCH_Msk, /**< Mask for enabling or disabling an interrupt on BCMATCH event. */
NRF_RADIO_INT_CRCOK_MASK = RADIO_INTENSET_CRCOK_Msk, /**< Mask for enabling or disabling an interrupt on CRCOK event. */
NRF_RADIO_INT_CRCERROR_MASK = RADIO_INTENSET_CRCERROR_Msk, /**< Mask for enabling or disabling an interrupt on CRCERROR event. */
NRF_RADIO_INT_FRAMESTART_MASK = RADIO_INTENSET_FRAMESTART_Msk, /**< Mask for enabling or disabling an interrupt on FRAMESTART event. */
NRF_RADIO_INT_EDEND_MASK = RADIO_INTENSET_EDEND_Msk, /**< Mask for enabling or disabling an interrupt on EDEND event. */
NRF_RADIO_INT_CCAIDLE_MASK = RADIO_INTENSET_CCAIDLE_Msk, /**< Mask for enabling or disabling an interrupt on CCAIDLE event. */
NRF_RADIO_INT_CCABUSY_MASK = RADIO_INTENSET_CCABUSY_Msk, /**< Mask for enabling or disabling an interrupt on CCABUSY event. */
NRF_RADIO_INT_PHYEND_MASK = RADIO_INTENSET_PHYEND_Msk, /**< Mask for enabling or disabling an interrupt on PHYEND event. */
} nrf_radio_int_mask_t;
/**
* @enum nrf_radio_short_mask_t
* @brief Types of RADIO shortcuts.
*/
typedef enum
{
NRF_RADIO_SHORT_READY_START_MASK = RADIO_SHORTS_READY_START_Msk, /**< Mask for setting shortcut between EVENT_READY and TASK_START. */
NRF_RADIO_SHORT_END_DISABLE_MASK = RADIO_SHORTS_END_DISABLE_Msk, /**< Mask for setting shortcut between EVENT_END and TASK_DISABLE. */
NRF_RADIO_SHORT_DISABLED_TXEN_MASK = RADIO_SHORTS_DISABLED_TXEN_Msk, /**< Mask for setting shortcut between EVENT_DISABLED and TASK_TXEN. */
NRF_RADIO_SHORT_DISABLED_RXEN_MASK = RADIO_SHORTS_DISABLED_RXEN_Msk, /**< Mask for setting shortcut between EVENT_DISABLED and TASK_RXEN. */
NRF_RADIO_SHORT_ADDRESS_RSSISTART_MASK = RADIO_SHORTS_ADDRESS_RSSISTART_Msk, /**< Mask for setting shortcut between EVENT_ADDRESS and TASK_RSSISTART. */
NRF_RADIO_SHORT_ADDRESS_BCSTART_MASK = RADIO_SHORTS_ADDRESS_BCSTART_Msk, /**< Mask for setting shortcut between EVENT_ADDRESS and TASK_BCSTART. */
NRF_RADIO_SHORT_END_START_MASK = RADIO_SHORTS_END_START_Msk, /**< Mask for setting shortcut between EVENT_END and TASK_START. */
NRF_RADIO_SHORT_RXREADY_CCASTART_MASK = RADIO_SHORTS_RXREADY_CCASTART_Msk, /**< Mask for setting shortcut between EVENT_RXREADY and TASK_CCASTART. */
NRF_RADIO_SHORT_CCAIDLE_TXEN_MASK = RADIO_SHORTS_CCAIDLE_TXEN_Msk, /**< Mask for setting shortcut between EVENT_CCAIDLE and TASK_TXEN. */
NRF_RADIO_SHORT_CCABUSY_DISABLE_MASK = RADIO_SHORTS_CCABUSY_DISABLE_Msk, /**< Mask for setting shortcut between EVENT_CCABUSY and TASK_DISABLE. */
NRF_RADIO_SHORT_FRAMESTART_BCSTART_MASK = RADIO_SHORTS_FRAMESTART_BCSTART_Msk, /**< Mask for setting shortcut between EVENT_FRAMESTART and TASK_BCSTART. */
NRF_RADIO_SHORT_READY_EDSTART_MASK = RADIO_SHORTS_READY_EDSTART_Msk, /**< Mask for setting shortcut between EVENT_READY and TASK_EDSTART. */
NRF_RADIO_SHORT_EDEND_DISABLE_MASK = RADIO_SHORTS_EDEND_DISABLE_Msk, /**< Mask for setting shortcut between EVENT_EDEND and TASK_DISABLE. */
NRF_RADIO_SHORT_TXREADY_START_MASK = RADIO_SHORTS_TXREADY_START_Msk, /**< Mask for setting shortcut between EVENT_TXREADY and TASK_START. */
NRF_RADIO_SHORT_RXREADY_START_MASK = RADIO_SHORTS_RXREADY_START_Msk, /**< Mask for setting shortcut between EVENT_RXREADY and TASK_START. */
NRF_RADIO_SHORT_PHYEND_DISABLE_MASK = RADIO_SHORTS_PHYEND_DISABLE_Msk, /**< Mask for setting shortcut between EVENT_PHYEND and TASK_DISABLE. */
NRF_RADIO_SHORT_PHYEND_START_MASK = RADIO_SHORTS_PHYEND_START_Msk, /**< Mask for setting shortcut between EVENT_PHYEND and TASK_START. */
} nrf_radio_short_mask_t;
/**
* @enum nrf_radio_cca_mode_t
* @brief Types of RADIO Clear Channel Assessment modes.
*/
typedef enum
{
NRF_RADIO_CCA_MODE_ED = RADIO_CCACTRL_CCAMODE_EdMode, /**< Energy Above Threshold. Will report busy whenever energy is detected above set threshold. */
NRF_RADIO_CCA_MODE_CARRIER = RADIO_CCACTRL_CCAMODE_CarrierMode, /**< Carrier Seen. Will report busy whenever compliant IEEE 802.15.4 signal is seen. */
NRF_RADIO_CCA_MODE_CARRIER_AND_ED = RADIO_CCACTRL_CCAMODE_CarrierAndEdMode, /**< Energy Above Threshold AND Carrier Seen. */
NRF_RADIO_CCA_MODE_CARRIER_OR_ED = RADIO_CCACTRL_CCAMODE_CarrierOrEdMode, /**< Energy Above Threshold OR Carrier Seen. */
} nrf_radio_cca_mode_t;
/**
* @enum nrf_radio_state_t
* @brief Types of RADIO States.
*/
typedef enum
{
NRF_RADIO_STATE_DISABLED = RADIO_STATE_STATE_Disabled, /**< No operations are going on inside the radio and the power consumption is at a minimum. */
NRF_RADIO_STATE_RX_RU = RADIO_STATE_STATE_RxRu, /**< The radio is ramping up and preparing for reception. */
NRF_RADIO_STATE_RX_IDLE = RADIO_STATE_STATE_RxIdle, /**< The radio is ready for reception to start. */
NRF_RADIO_STATE_RX = RADIO_STATE_STATE_Rx, /**< Reception has been started. */
NRF_RADIO_STATE_RX_DISABLE = RADIO_STATE_STATE_RxDisable, /**< The radio is disabling the receiver. */
NRF_RADIO_STATE_TX_RU = RADIO_STATE_STATE_TxRu, /**< The radio is ramping up and preparing for transmission. */
NRF_RADIO_STATE_TX_IDLE = RADIO_STATE_STATE_TxIdle, /**< The radio is ready for transmission to start. */
NRF_RADIO_STATE_TX = RADIO_STATE_STATE_Tx, /**< The radio is transmitting a packet. */
NRF_RADIO_STATE_TX_DISABLE = RADIO_STATE_STATE_TxDisable, /**< The radio is disabling the transmitter. */
} nrf_radio_state_t;
/**
* @enum nrf_radio_crc_status_t
* @brief Types of CRC status.
*/
typedef enum
{
NRF_RADIO_CRC_STATUS_ERROR = RADIO_CRCSTATUS_CRCSTATUS_CRCError, /**< Packet received with CRC error. */
NRF_RADIO_CRC_STATUS_OK = RADIO_CRCSTATUS_CRCSTATUS_CRCOk, /**< Packet received with CRC ok. */
} nrf_radio_crc_status_t;
/**
* @enum nrf_radio_mode_t
* @brief Types of RADIO modes (data rate and modulation).
*/
typedef enum
{
NRF_RADIO_MODE_NRF_1MBIT = RADIO_MODE_MODE_Nrf_1Mbit, /**< 1Mbit/s Nordic proprietary radio mode. */
NRF_RADIO_MODE_NRF_2MBIT = RADIO_MODE_MODE_Nrf_2Mbit, /**< 2Mbit/s Nordic proprietary radio mode. */
NRF_RADIO_MODE_BLE_1MBIT = RADIO_MODE_MODE_Ble_1Mbit, /**< 1 Mbit/s Bluetooth Low Energy. */
NRF_RADIO_MODE_BLE_2MBIT = RADIO_MODE_MODE_Ble_2Mbit, /**< 2 Mbit/s Bluetooth Low Energy. */
NRF_RADIO_MODE_IEEE802154_250KBIT = RADIO_MODE_MODE_Ieee802154_250Kbit, /**< IEEE 802.15.4-2006 250 kbit/s. */
} nrf_radio_mode_t;
/**
* @enum nrf_radio_preamble_length_t
* @brief Types of preamble length.
*/
typedef enum
{
NRF_RADIO_PREAMBLE_LENGTH_8BIT = RADIO_PCNF0_PLEN_8bit, /**< 8-bit preamble. */
NRF_RADIO_PREAMBLE_LENGTH_16BIT = RADIO_PCNF0_PLEN_16bit, /**< 16-bit preamble. */
NRF_RADIO_PREAMBLE_LENGTH_32BIT_ZERO = RADIO_PCNF0_PLEN_32bitZero, /**< 32-bit zero preamble used for IEEE 802.15.4. */
NRF_RADIO_PREAMBLE_LENGTH_LONG_RANGE = RADIO_PCNF0_PLEN_LongRange, /**< Preamble - used for BTLE Long Range. */
} nrf_radio_preamble_length_t;
/**
* @enum nrf_radio_crc_includes_addr_t
* @brief Types of CRC calculatons regarding address.
*/
typedef enum
{
NRF_RADIO_CRC_INCLUDES_ADDR_INCLUDE = RADIO_CRCCNF_SKIPADDR_Include, /**< CRC calculation includes address field. */
NRF_RADIO_CRC_INCLUDES_ADDR_SKIP = RADIO_CRCCNF_SKIPADDR_Skip, /**< CRC calculation does not include address field. */
NRF_RADIO_CRC_INCLUDES_ADDR_IEEE802154 = RADIO_CRCCNF_SKIPADDR_Ieee802154, /**< CRC calculation as per 802.15.4 standard. */
} nrf_radio_crc_includes_addr_t;
/**
* @enum nrf_radio_ramp_up_mode_t
* @brief Types of radio ramp-up mode.
*/
typedef enum
{
NRF_RADIO_RAMP_UP_MODE_DEFAULT = RADIO_MODECNF0_RU_Default, /**< Default ramp-up mode. */
NRF_RADIO_RAMP_UP_MODE_FAST = RADIO_MODECNF0_RU_Fast /**< Fast ramp-up mode. */
} nrf_radio_ramp_up_mode_t;
/**
* @brief Function for enabling interrupts.
*
* @param[in] radio_int_mask Mask of interrupts.
*/
__STATIC_INLINE void nrf_radio_int_enable(uint32_t radio_int_mask);
/**
* @brief Function for disabling interrupts.
*
* @param[in] radio_int_mask Mask of interrupts.
*/
__STATIC_INLINE void nrf_radio_int_disable(uint32_t radio_int_mask);
/**
* @brief Function for getting the state of a specific interrupt.
*
* @param[in] radio_int_mask Interrupt.
*
* @retval true If the interrupt is not enabled.
* @retval false If the interrupt is enabled.
*/
__STATIC_INLINE bool nrf_radio_int_get(nrf_radio_int_mask_t radio_int_mask);
/**
* @brief Function for getting the address of a specific task.
*
* This function can be used by the PPI module.
*
* @param[in] radio_task Task.
*/
__STATIC_INLINE uint32_t * nrf_radio_task_address_get(nrf_radio_task_t radio_task);
/**
* @brief Function for setting a specific task.
*
* @param[in] radio_task Task.
*/
__STATIC_INLINE void nrf_radio_task_trigger(nrf_radio_task_t radio_task);
/**
* @brief Function for getting address of a specific event.
*
* This function can be used by the PPI module.
*
* @param[in] radio_event Event.
*/
__STATIC_INLINE uint32_t * nrf_radio_event_address_get(nrf_radio_event_t radio_event);
/**
* @brief Function for clearing a specific event.
*
* @param[in] radio_event Event.
*/
__STATIC_INLINE void nrf_radio_event_clear(nrf_radio_event_t radio_event);
/**
* @brief Function for getting the state of a specific event.
*
* @param[in] radio_event Event.
*
* @retval true If the event is not set.
* @retval false If the event is set.
*/
__STATIC_INLINE bool nrf_radio_event_get(nrf_radio_event_t radio_event);
/**
* @brief Function for setting shortcuts.
*
* @param[in] radio_short_mask Mask of shortcuts.
*
*/
__STATIC_INLINE void nrf_radio_shorts_enable(uint32_t radio_short_mask);
/**
* @brief Function for clearing shortcuts.
*
* @param[in] radio_short_mask Mask of shortcuts.
*
*/
__STATIC_INLINE void nrf_radio_shorts_disable(uint32_t radio_short_mask);
/**
* @brief Function for setting shortcuts.
*
* @param[in] radio_short_mask Mask of shortcuts.
*
*/
__STATIC_INLINE void nrf_radio_shorts_set(uint32_t radio_short_mask);
/**
* @brief Function for getting shortcuts.
*
* @return Mask of shortcuts.
*
*/
__STATIC_INLINE uint32_t nrf_radio_shorts_get(void);
/**
* @brief Function for getting present state of the radio module.
*/
__STATIC_INLINE nrf_radio_state_t nrf_radio_state_get(void);
/**
* @brief Function for setting Packet Pointer to given location in memory.
*
* @param[in] p_radio_packet_ptr Pointer to tx or rx packet buffer.
*/
__STATIC_INLINE void nrf_radio_packet_ptr_set(const void * p_radio_packet_ptr);
/**
* @brief Function for getting CRC status of last received packet.
*/
__STATIC_INLINE nrf_radio_crc_status_t nrf_radio_crc_status_get(void);
/**
* @brief Function for setting Clear Channel Assessment mode.
*
* @param[in] radio_cca_mode Mode of CCA
*/
__STATIC_INLINE void nrf_radio_cca_mode_set(nrf_radio_cca_mode_t radio_cca_mode);
/**
* @brief Function for setting CCA Energy Busy Threshold.
*
* @param[in] radio_cca_ed_threshold Energy Detection threshold value.
*/
__STATIC_INLINE void nrf_radio_cca_ed_threshold_set(uint8_t radio_cca_ed_threshold);
/**
* @brief Function for setting CCA Correlator Busy Threshold.
*
* @param[in] radio_cca_corr_threshold Correlator Busy Threshold.
*/
__STATIC_INLINE void nrf_radio_cca_corr_threshold_set(uint8_t radio_cca_corr_threshold_set);
/**
* @brief Function for setting limit of occurances above Correlator Threshold.
*
* When not equal to zero the correlator based signal detect is enabled.
*
* @param[in] radio_cca_corr_cnt Limit of occurances above Correlator Threshold
*/
__STATIC_INLINE void nrf_radio_cca_corr_counter_set(uint8_t radio_cca_corr_counter_set);
/**
* @brief Function for setting Radio data rate and modulation settings.
*
* @param[in] radio_mode Mode of radio data rate and modulation.
*/
__STATIC_INLINE void nrf_radio_mode_set(nrf_radio_mode_t radio_mode);
/**
* @brief Function for setting Length of LENGTH field in number of bits.
*
* @param[in] radio_length_length Length of LENGTH field in number of bits.
*/
__STATIC_INLINE void nrf_radio_config_length_field_length_set(uint8_t radio_length_length);
/**
* @brief Function for setting length of preamble on air.
*
* @param[in] radio_preamble_length Length of preamble on air.
*/
__STATIC_INLINE void nrf_radio_config_preamble_length_set(
nrf_radio_preamble_length_t radio_preamble_length);
/**
* @brief Function for setting if LENGTH field contains CRC.
*
* @param[in] radio_length_contains_crc True if LENGTH field should contain CRC.
*/
__STATIC_INLINE void nrf_radio_config_crc_included_set(bool radio_length_contains_crc);
/**
* @brief Function for setting maximum length of packet payload.
*
* @param[in] radio_max_packet_length Maximum length of packet payload.
*/
__STATIC_INLINE void nrf_radio_config_max_length_set(uint8_t radio_max_packet_length);
/**
* @brief Function for setting CRC length.
*
* @param[in] radio_crc_length CRC length in number of bytes [0-3].
*/
__STATIC_INLINE void nrf_radio_crc_length_set(uint8_t radio_crc_length);
/**
* @brief Function for setting if address filed should be included or excluded from CRC calculation.
*
* @param[in] radio_crc_skip_address Include or exclude packet address field out of CRC.
*/
__STATIC_INLINE void nrf_radio_crc_includes_address_set(
nrf_radio_crc_includes_addr_t radio_crc_skip_address);
/**
* @brief Function for setting CRC polynominal.
*
* @param[in] radio_crc_polynominal CRC polynominal to set.
*/
__STATIC_INLINE void nrf_radio_crc_polynominal_set(uint32_t radio_crc_polynominal);
/**
* @brief Function for getting CRC polynominal.
*
* @return CRC polynominal.
*/
__STATIC_INLINE uint32_t nrf_radio_crc_polynominal_get(void);
/**
* @brief Function for getting RSSI sample result.
*
* @note The value is a positive value while the actual received signal is a negative value.
* Actual received signal strength is therefore as follows:
* received signal strength = - returned_value dBm .
*/
__STATIC_INLINE uint8_t nrf_radio_rssi_sample_get(void);
/**
* @brief Function for setting MAC Header Match Unit search pattern configuration.
*
* @param[in] radio_mhmu_search_pattern Search Pattern Configuration.
*/
__STATIC_INLINE void nrf_radio_mhmu_search_pattern_set(uint32_t radio_mhmu_search_pattern);
/**
* @brief Function for setting MAC Header Match Unit pattern mask configuration.
*
* @param[in] radio_mhmu_pattern_mask Pattern mask.
*/
__STATIC_INLINE void nrf_radio_mhmu_pattern_mask_set(uint32_t radio_mhmu_pattern_mask);
/**
* @brief Function for setting radio ramp-up mode.
*
* @param[in] ramp_up_mode Radio ramp-up mode.
*/
__STATIC_INLINE void nrf_radio_ramp_up_mode_set(nrf_radio_ramp_up_mode_t ramp_up_mode);
/**
* @brief Function for setting radio frequency.
*
* @param[in] radio_frequency Frequency above 2400 MHz [MHz]
*/
__STATIC_INLINE void nrf_radio_frequency_set(uint32_t radio_frequency);
/**
* @brief Function for getting radio frequency.
*
* @returns Frequency above 2400 MHz [MHz]
*/
__STATIC_INLINE uint32_t nrf_radio_frequency_get(void);
/**
* @brief Function for setting radio transmit power.
*
* @param[in] radio_tx_power Transmit power of the radio.
*/
__STATIC_INLINE void nrf_radio_tx_power_set(int8_t radio_tx_power);
/**
* @brief Function for setting Inter Frame Spacing
*
* @param[in] radio_ifs Inter frame spacing [us].
*/
__STATIC_INLINE void nrf_radio_ifs_set(uint32_t radio_ifs);
/**
* @brief Function for getting Inter Frame Spacing
*
* @return Current Inter Frame Spacing
*/
__STATIC_INLINE uint32_t nrf_radio_ifs_get(void);
/**
* @brief Function for setting Bit counter compare.
*
* @param[in] radio_bcc Bit counter compare [bits].
*/
__STATIC_INLINE void nrf_radio_bcc_set(uint32_t radio_bcc);
/**
* @brief Function for getting Bit counter compare.
*/
__STATIC_INLINE uint32_t nrf_radio_bcc_get(void);
/**
* @brief Function for getting Energy Detection level.
*/
__STATIC_INLINE uint8_t nrf_radio_ed_sample_get(void);
/**
* @brief Function for setting number of iterations to perform ED scan.
*
* @param[in] radio_ed_loop_count Number of iterations during ED procedure.
*/
__STATIC_INLINE void nrf_radio_ed_loop_count_set(uint32_t radio_ed_loop_count);
/**
* @brief Function for setting power mode of the radio peripheral.
*
* @param[in] radio_power If radio should powered on.
*/
__STATIC_INLINE void nrf_radio_power_set(bool radio_power);
/**
*@}
**/
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE void nrf_radio_int_enable(uint32_t radio_int_mask)
{
NRF_RADIO->INTENSET = radio_int_mask;
}
__STATIC_INLINE void nrf_radio_int_disable(uint32_t radio_int_mask)
{
NRF_RADIO->INTENCLR = radio_int_mask;
}
__STATIC_INLINE bool nrf_radio_int_get(nrf_radio_int_mask_t radio_int_mask)
{
return (bool)(NRF_RADIO->INTENCLR & radio_int_mask);
}
__STATIC_INLINE uint32_t * nrf_radio_task_address_get(nrf_radio_task_t radio_task)
{
return (uint32_t *)((uint8_t *)NRF_RADIO + radio_task);
}
__STATIC_INLINE void nrf_radio_task_trigger(nrf_radio_task_t radio_task)
{
*((volatile uint32_t *)((uint8_t *)NRF_RADIO + radio_task)) = NRF_RADIO_TASK_SET;
}
__STATIC_INLINE uint32_t * nrf_radio_event_address_get(nrf_radio_event_t radio_event)
{
return (uint32_t *)((uint8_t *)NRF_RADIO + radio_event);
}
__STATIC_INLINE void nrf_radio_event_clear(nrf_radio_event_t radio_event)
{
*((volatile uint32_t *)((uint8_t *)NRF_RADIO + radio_event)) = NRF_RADIO_EVENT_CLEAR;
#if __CORTEX_M == 0x04
volatile uint32_t dummy = *((volatile uint32_t *)((uint8_t *)NRF_RADIO + radio_event));
(void)dummy;
#endif
}
__STATIC_INLINE bool nrf_radio_event_get(nrf_radio_event_t radio_event)
{
return (bool)*((volatile uint32_t *)((uint8_t *)NRF_RADIO + radio_event));
}
__STATIC_INLINE void nrf_radio_shorts_enable(uint32_t radio_short_mask)
{
NRF_RADIO->SHORTS |= radio_short_mask;
}
__STATIC_INLINE void nrf_radio_shorts_disable(uint32_t radio_short_mask)
{
NRF_RADIO->SHORTS &= ~radio_short_mask;
}
__STATIC_INLINE void nrf_radio_shorts_set(uint32_t radio_short_mask)
{
NRF_RADIO->SHORTS = radio_short_mask;
}
__STATIC_INLINE uint32_t nrf_radio_shorts_get(void)
{
return NRF_RADIO->SHORTS;
}
__STATIC_INLINE nrf_radio_state_t nrf_radio_state_get(void)
{
return (nrf_radio_state_t)NRF_RADIO->STATE;
}
__STATIC_INLINE void nrf_radio_packet_ptr_set(const void * p_radio_packet_ptr)
{
NRF_RADIO->PACKETPTR = (uint32_t)p_radio_packet_ptr;
}
__STATIC_INLINE nrf_radio_crc_status_t nrf_radio_crc_status_get(void)
{
return (nrf_radio_crc_status_t)NRF_RADIO->CRCSTATUS;
}
__STATIC_INLINE void nrf_radio_cca_mode_set(nrf_radio_cca_mode_t radio_cca_mode)
{
NRF_RADIO->CCACTRL &= (~RADIO_CCACTRL_CCAMODE_Msk);
NRF_RADIO->CCACTRL |= ((uint32_t)radio_cca_mode << RADIO_CCACTRL_CCAMODE_Pos);
}
__STATIC_INLINE void nrf_radio_cca_ed_threshold_set(uint8_t radio_cca_ed_threshold)
{
NRF_RADIO->CCACTRL &= (~RADIO_CCACTRL_CCAEDTHRES_Msk);
NRF_RADIO->CCACTRL |= ((uint32_t)radio_cca_ed_threshold << RADIO_CCACTRL_CCAEDTHRES_Pos);
}
__STATIC_INLINE void nrf_radio_cca_corr_threshold_set(uint8_t radio_cca_corr_threshold_set)
{
NRF_RADIO->CCACTRL &= (~RADIO_CCACTRL_CCACORRTHRES_Msk);
NRF_RADIO->CCACTRL |=
((uint32_t)radio_cca_corr_threshold_set << RADIO_CCACTRL_CCACORRTHRES_Pos);
}
__STATIC_INLINE void nrf_radio_cca_corr_counter_set(uint8_t radio_cca_corr_counter_set)
{
NRF_RADIO->CCACTRL &= (~RADIO_CCACTRL_CCACORRCNT_Msk);
NRF_RADIO->CCACTRL |= ((uint32_t)radio_cca_corr_counter_set << RADIO_CCACTRL_CCACORRCNT_Pos);
}
__STATIC_INLINE void nrf_radio_mode_set(nrf_radio_mode_t radio_mode)
{
NRF_RADIO->MODE = ((uint32_t)radio_mode << RADIO_MODE_MODE_Pos);
}
__STATIC_INLINE void nrf_radio_config_length_field_length_set(uint8_t radio_length_length)
{
NRF_RADIO->PCNF0 &= (~RADIO_PCNF0_LFLEN_Msk);
NRF_RADIO->PCNF0 |= ((uint32_t)radio_length_length << RADIO_PCNF0_LFLEN_Pos);
}
__STATIC_INLINE void nrf_radio_config_preamble_length_set(
nrf_radio_preamble_length_t radio_preamble_length)
{
NRF_RADIO->PCNF0 &= (~RADIO_PCNF0_PLEN_Msk);
NRF_RADIO->PCNF0 |= ((uint32_t)radio_preamble_length << RADIO_PCNF0_PLEN_Pos);
}
__STATIC_INLINE void nrf_radio_config_crc_included_set(bool radio_length_contains_crc)
{
NRF_RADIO->PCNF0 &= (~RADIO_PCNF0_CRCINC_Msk);
NRF_RADIO->PCNF0 |= ((uint32_t)radio_length_contains_crc << RADIO_PCNF0_CRCINC_Pos);
}
__STATIC_INLINE void nrf_radio_config_max_length_set(uint8_t radio_max_packet_length)
{
NRF_RADIO->PCNF1 &= (~RADIO_PCNF1_MAXLEN_Msk);
NRF_RADIO->PCNF1 |= ((uint32_t)radio_max_packet_length << RADIO_PCNF1_MAXLEN_Pos);
}
__STATIC_INLINE void nrf_radio_crc_length_set(uint8_t radio_crc_length)
{
NRF_RADIO->CRCCNF &= (~RADIO_CRCCNF_LEN_Msk);
NRF_RADIO->CRCCNF |= ((uint32_t)radio_crc_length << RADIO_CRCCNF_LEN_Pos);
}
__STATIC_INLINE void nrf_radio_crc_includes_address_set(
nrf_radio_crc_includes_addr_t radio_crc_skip_address)
{
NRF_RADIO->CRCCNF &= (~RADIO_CRCCNF_SKIPADDR_Msk);
NRF_RADIO->CRCCNF |= ((uint32_t)radio_crc_skip_address << RADIO_CRCCNF_SKIPADDR_Pos);
}
__STATIC_INLINE void nrf_radio_crc_polynominal_set(uint32_t radio_crc_polynominal)
{
NRF_RADIO->CRCPOLY = (radio_crc_polynominal << RADIO_CRCPOLY_CRCPOLY_Pos);
}
__STATIC_INLINE uint32_t nrf_radio_crc_polynominal_get(void)
{
return (NRF_RADIO->CRCPOLY & RADIO_CRCPOLY_CRCPOLY_Msk) >> RADIO_CRCPOLY_CRCPOLY_Pos;
}
__STATIC_INLINE uint8_t nrf_radio_rssi_sample_get(void)
{
return (uint8_t)(((NRF_RADIO->RSSISAMPLE) & RADIO_RSSISAMPLE_RSSISAMPLE_Msk) >>
RADIO_RSSISAMPLE_RSSISAMPLE_Pos);
}
__STATIC_INLINE void nrf_radio_mhmu_search_pattern_set(uint32_t radio_mhmu_search_pattern)
{
NRF_RADIO->MHRMATCHCONF = radio_mhmu_search_pattern;
}
__STATIC_INLINE void nrf_radio_mhmu_pattern_mask_set(uint32_t radio_mhmu_pattern_mask)
{
NRF_RADIO->MHRMATCHMAS = radio_mhmu_pattern_mask;
}
__STATIC_INLINE void nrf_radio_ramp_up_mode_set(nrf_radio_ramp_up_mode_t ramp_up_mode)
{
NRF_RADIO->MODECNF0 &= (~RADIO_MODECNF0_RU_Msk);
NRF_RADIO->MODECNF0 |= ((uint32_t)ramp_up_mode << RADIO_MODECNF0_RU_Pos);
}
__STATIC_INLINE void nrf_radio_frequency_set(uint32_t radio_frequency)
{
NRF_RADIO->FREQUENCY = radio_frequency;
}
__STATIC_INLINE uint32_t nrf_radio_frequency_get(void)
{
return NRF_RADIO->FREQUENCY;
}
__STATIC_INLINE void nrf_radio_tx_power_set(int8_t radio_tx_power)
{
NRF_RADIO->TXPOWER = (uint8_t)radio_tx_power;
}
__STATIC_INLINE void nrf_radio_ifs_set(uint32_t radio_ifs)
{
NRF_RADIO->TIFS = radio_ifs;
}
__STATIC_INLINE uint32_t nrf_radio_ifs_get(void)
{
return NRF_RADIO->TIFS & RADIO_TIFS_TIFS_Msk;
}
__STATIC_INLINE void nrf_radio_bcc_set(uint32_t radio_bcc)
{
NRF_RADIO->BCC = radio_bcc;
}
__STATIC_INLINE uint32_t nrf_radio_bcc_get(void)
{
return NRF_RADIO->BCC;
}
__STATIC_INLINE uint8_t nrf_radio_ed_sample_get(void)
{
return (uint8_t)NRF_RADIO->EDSAMPLE;
}
__STATIC_INLINE void nrf_radio_ed_loop_count_set(uint32_t radio_ed_loop_count)
{
NRF_RADIO->EDCNT = (radio_ed_loop_count & 0x001FFFFF);
}
__STATIC_INLINE void nrf_radio_power_set(bool radio_power)
{
NRF_RADIO->POWER = (uint32_t)radio_power;
}
#endif /* SUPPRESS_INLINE_IMPLEMENTATION */
#ifdef __cplusplus
}
#endif
#endif /* NRF_RADIO_H__ */

View file

@ -1,168 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements ACK timeout procedure for the 802.15.4 driver.
*
*/
#include "nrf_802154_ack_timeout.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_notification.h"
#include "nrf_802154_request.h"
#include "timer_scheduler/nrf_802154_timer_sched.h"
#define RETRY_DELAY 500 ///< Procedure is delayed by this time if cannot be performed at the moment.
#define MAX_RETRY_DELAY 1000000 ///< Maximal allowed delay of procedure retry.
static void timeout_timer_retry(void);
static uint32_t m_timeout = NRF_802154_ACK_TIMEOUT_DEFAULT_TIMEOUT; ///< ACK timeout in us.
static nrf_802154_timer_t m_timer; ///< Timer used to notify when we are waiting too long for ACK.
static volatile bool m_procedure_is_active;
static const uint8_t * mp_frame;
static void notify_tx_error(bool result)
{
if (result)
{
nrf_802154_notify_transmit_failed(mp_frame, NRF_802154_TX_ERROR_NO_ACK);
}
}
static void timeout_timer_fired(void * p_context)
{
(void)p_context;
if (m_procedure_is_active)
{
if (nrf_802154_request_receive(NRF_802154_TERM_802154,
REQ_ORIG_ACK_TIMEOUT,
notify_tx_error,
false))
{
m_procedure_is_active = false;
}
else
{
timeout_timer_retry();
}
}
}
static void timeout_timer_retry(void)
{
m_timer.dt += RETRY_DELAY;
assert(m_timer.dt <= MAX_RETRY_DELAY);
nrf_802154_timer_sched_add(&m_timer, true);
}
static void timeout_timer_start(void)
{
m_timer.callback = timeout_timer_fired;
m_timer.p_context = NULL;
m_timer.t0 = nrf_802154_timer_sched_time_get();
m_timer.dt = m_timeout;
m_procedure_is_active = true;
nrf_802154_timer_sched_add(&m_timer, true);
}
static void timeout_timer_stop(void)
{
m_procedure_is_active = false;
// To make sure `timeout_timer_fired()` detects that procedure is being stopped if it preempts
// this function.
__DMB();
nrf_802154_timer_sched_remove(&m_timer);
}
void nrf_802154_ack_timeout_time_set(uint32_t time)
{
m_timeout = time;
}
bool nrf_802154_ack_timeout_tx_started_hook(const uint8_t * p_frame)
{
mp_frame = p_frame;
timeout_timer_start();
return true;
}
bool nrf_802154_ack_timeout_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig)
{
bool result;
if (!m_procedure_is_active || req_orig == REQ_ORIG_ACK_TIMEOUT)
{
// Ignore if procedure is not running or self-request.
result = true;
}
else if (term_lvl >= NRF_802154_TERM_802154)
{
// Stop procedure only if termination level is high enough.
timeout_timer_stop();
result = true;
}
else
{
result = false;
}
return result;
}
void nrf_802154_ack_timeout_transmitted_hook(const uint8_t * p_frame)
{
assert((p_frame == mp_frame) || (!m_procedure_is_active));
timeout_timer_stop();
}
bool nrf_802154_ack_timeout_tx_failed_hook(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
(void)error;
assert((p_frame == mp_frame) || (!m_procedure_is_active));
timeout_timer_stop();
return true;
}

View file

@ -1,101 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_ACK_TIMEOUT_H__
#define NRF_802154_ACK_TIMEOUT_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_const.h"
#include "nrf_802154_types.h"
/**
* @defgroup nrf_802154_csma_ca 802.15.4 driver ACK timeout support
* @{
* @ingroup nrf_802154
* @brief ACK timeout feature.
*/
/**
* @brief Set timeout time for ACK timeout feature.
*
* @param[in] time Timeout time in us.
* Default value is defined in nrf_802154_config.h.
*/
void nrf_802154_ack_timeout_time_set(uint32_t time);
/**
* @brief Abort started ACK timeout procedure.
*
* @param[in] term_lvl Termination level set by request aborting ongoing operation.
* @param[in] req_orig Module that originates this request.
*
* If ACK timeout procedure is not running during call, this function does nothing.
*
* @retval true ACK timeout procedure han been stopped.
*/
bool nrf_802154_ack_timeout_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig);
/**
* @brief Handler of transmitted event.
*
* @param[in] p_frame Pointer to the buffer containing transmitted frame.
*/
void nrf_802154_ack_timeout_transmitted_hook(const uint8_t * p_frame);
/**
* @brief Handler of TX failed event.
*
* @param[in] p_frame Pointer to the buffer containing frame that was not transmitted.
* @param[in] error Cause of failed transmission.
*
* @retval true TX failed event should be propagated to the MAC layer.
* @retval false TX failed event should not be propagated to the MAC layer. It is handled
* internally.
*/
bool nrf_802154_ack_timeout_tx_failed_hook(const uint8_t * p_frame, nrf_802154_tx_error_t error);
/**
* @brief Handler of TX started event.
*
* @param[in] p_frame Pointer to the buffer containing frame being transmitted.
*
* @retval true TX started event should be propagated to the MAC layer.
* @retval false TX started event should not be propagated to the MAC layer. It is handled
* internally.
*/
bool nrf_802154_ack_timeout_tx_started_hook(const uint8_t * p_frame);
/**
*@}
**/
#endif // NRF_802154_CSMA_CA_H__

View file

@ -1,257 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements CSMA-CA procedure for the 802.15.4 driver.
*
*/
#include "nrf_802154_csma_ca.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "nrf_802154_config.h"
#include "nrf_802154_const.h"
#include "nrf_802154_debug.h"
#include "nrf_802154_notification.h"
#include "nrf_802154_request.h"
#include "timer_scheduler/nrf_802154_timer_sched.h"
#if NRF_802154_CSMA_CA_ENABLED
static uint8_t m_nb; ///< The number of times the CSMA-CA algorithm was required to back off while attempting the current transmission.
static uint8_t m_be; ///< Backoff exponent, which is related to how many backoff periods a device shall wait before attempting to assess a channel.
static const uint8_t * mp_psdu; ///< Pointer to PSDU of the frame being transmitted.
static nrf_802154_timer_t m_timer; ///< Timer used to back off during CSMA-CA procedure.
static bool m_is_running; ///< Indicates if CSMA-CA procedure is running.
/**
* @brief Perform appropriate actions for busy channel conditions.
*
* According to CSMA-CA description in 802.15.4 specification, when channel is busy NB and BE shall
* be incremented and the device shall wait random delay before next CCA procedure. If NB reaches
* macMaxCsmaBackoffs procedure fails.
*
* @retval true Procedure failed and TX failure should be notified to the next higher layer.
* @retval false Procedure is still ongoing and TX failure should be handled internally.
*/
static bool channel_busy(void);
/**
* @brief Check if CSMA-CA is ongoing.
*
* @retval true CSMA-CA is running.
* @retval false CSMA-CA is not running currently.
*/
static bool procedure_is_running(void)
{
return m_is_running;
}
/**
* @brief Stop CSMA-CA procedure.
*/
static void procedure_stop(void)
{
m_is_running = false;
}
/**
* Notify MAC layer that channel is busy if tx request failed and there are no retries left.
*
* @param[in] result Result of TX request.
*/
static void notify_busy_channel(bool result)
{
if (!result && (m_nb >= (NRF_802154_CSMA_CA_MAX_CSMA_BACKOFFS - 1)))
{
nrf_802154_notify_transmit_failed(mp_psdu, NRF_802154_TX_ERROR_BUSY_CHANNEL);
}
}
/**
* @brief Perform CCA procedure followed by frame transmission.
*
* If transmission is requested, CSMA-CA module waits for notification from the FSM module.
* If transmission request fails, CSMA-CA module performs procedure for busy channel condition
* @sa channel_busy().
*
* @param[in] p_context Unused variable passed from the Timer Scheduler module.
*/
static void frame_transmit(void * p_context)
{
(void)p_context;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMA_FRAME_TRANSMIT);
if (procedure_is_running())
{
if (!nrf_802154_request_transmit(NRF_802154_TERM_NONE,
REQ_ORIG_CSMA_CA,
mp_psdu,
true,
true,
notify_busy_channel))
{
(void)channel_busy();
}
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMA_FRAME_TRANSMIT);
}
/**
* @brief Delay CCA procedure for random (2^BE - 1) unit backoff periods.
*/
static void random_backoff_start(void)
{
uint8_t backoff_periods = rand() % (1 << m_be);
m_timer.callback = frame_transmit;
m_timer.p_context = NULL;
m_timer.t0 = nrf_802154_timer_sched_time_get();
m_timer.dt = backoff_periods * UNIT_BACKOFF_PERIOD;
nrf_802154_timer_sched_add(&m_timer, false);
}
static bool channel_busy(void)
{
bool result = true;
if (procedure_is_running())
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMA_CHANNEL_BUSY);
m_nb++;
if (m_be < NRF_802154_CSMA_CA_MAX_BE)
{
m_be++;
}
if (m_nb < NRF_802154_CSMA_CA_MAX_CSMA_BACKOFFS)
{
random_backoff_start();
result = false;
}
else
{
procedure_stop();
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMA_CHANNEL_BUSY);
}
return result;
}
void nrf_802154_csma_ca_start(const uint8_t * p_data)
{
assert(!procedure_is_running());
mp_psdu = p_data;
m_nb = 0;
m_be = NRF_802154_CSMA_CA_MIN_BE;
m_is_running = true;
random_backoff_start();
}
bool nrf_802154_csma_ca_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig)
{
bool result = false;
// Stop CSMA-CA only if request by the core or the higher layer.
if ((req_orig != REQ_ORIG_CORE) && (req_orig != REQ_ORIG_HIGHER_LAYER))
{
return true;
}
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMA_ABORT);
if (term_lvl >= NRF_802154_TERM_802154)
{
// Stop CSMA-CA if termination level is high enough.
nrf_802154_timer_sched_remove(&m_timer);
procedure_stop();
result = true;
}
else if (!procedure_is_running())
{
// Return success in case procedure is already stopped.
result = true;
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMA_ABORT);
return result;
}
bool nrf_802154_csma_ca_tx_failed_hook(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
(void)error;
bool result = true;
if (p_frame == mp_psdu)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMA_TX_FAILED);
result = channel_busy();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMA_TX_FAILED);
}
return result;
}
bool nrf_802154_csma_ca_tx_started_hook(const uint8_t * p_frame)
{
if (p_frame == mp_psdu)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMA_TX_STARTED);
assert(!nrf_802154_timer_sched_is_running(&m_timer));
procedure_stop();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMA_TX_STARTED);
}
return true;
}
#endif // NRF_802154_CSMA_CA_ENABLED

View file

@ -1,105 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_CSMA_CA_H__
#define NRF_802154_CSMA_CA_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_const.h"
#include "nrf_802154_types.h"
/**
* @defgroup nrf_802154_csma_ca 802.15.4 driver CSMA-CA support
* @{
* @ingroup nrf_802154
* @brief CSMA-CA procedure.
*/
/**
* @brief Start CSMA-CA procedure for transmission of given frame.
*
* If CSMA-CA procedure is successful and frame is transmitted @sa nrf_802154_tx_started()
* function is called. If CSMA/CA procedure failed and frame cannot be transmitted due to busy
* channel @sa nrf_802154_transmit_failed() function is called.
*
* @note CSMA-CA does not timeout waiting for ACK automatically. Waiting for ACK shall be timed out
* by the next layer. ACK timeout timer shall start when @sa nrf_802154_tx_started()
* function is called.
*
* @param[in] p_data Pointer to PSDU of frame that should be transmitted.
*/
void nrf_802154_csma_ca_start(const uint8_t * p_data);
/**
* @brief Abort ongoing CSMA-CA procedure.
*
* @note This function shall not be called during @sa nrf_802154_csma_ca_start execution
* (i.e. from ISR with higher priority). It would result with unrecoverable runtime error.
*
* If CSMA-CA is not running during call, this function does nothing and returns true.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @retval true CSMA-CA procedure is not running anymore.
* @retval false CSMA-CA cannot be stopped due to too low termination level.
*/
bool nrf_802154_csma_ca_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig);
/**
* @brief Handler of TX failed event.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that was not transmitted.
* @param[in] error Cause of failed transmission.
*
* @retval true TX failed event should be propagated to the MAC layer.
* @retval false TX failed event should not be propagated to the MAC layer. It is handled
* internally.
*/
bool nrf_802154_csma_ca_tx_failed_hook(const uint8_t * p_frame, nrf_802154_tx_error_t error);
/**
* @brief Handler of TX started event.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that is being transmitted.
*
* @retval true TX started event should be propagated to the MAC layer.
* @retval false TX started event should not be propagated to the MAC layer. It is handled
* internally.
*/
bool nrf_802154_csma_ca_tx_started_hook(const uint8_t * p_frame);
/**
*@}
**/
#endif // NRF_802154_CSMA_CA_H__

View file

@ -1,365 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements delayed transmission and reception features.
*
*/
#include "nrf_802154_delayed_trx.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_config.h"
#include "nrf_802154_const.h"
#include "nrf_802154_notification.h"
#include "nrf_802154_pib.h"
#include "nrf_802154_procedures_duration.h"
#include "nrf_802154_request.h"
#include "nrf_802154_rsch.h"
#include "timer_scheduler/nrf_802154_timer_sched.h"
#define TX_SETUP_TIME 190u ///< Time [us] needed to change channel, stop rx and setup tx procedure.
#define RX_SETUP_TIME 190u ///< Time [us] needed to change channel, stop tx and setup rx procedure.
static const uint8_t * mp_tx_psdu; ///< Pointer to PHR + PSDU of the frame requested to transmit.
static bool m_tx_cca; ///< If CCA should be performed prior to transmission.
static uint8_t m_tx_channel; ///< Channel number on which transmission should be performed.
static nrf_802154_timer_t m_timeout_timer; ///< Timer for delayed RX timeout handling.
static uint8_t m_rx_channel; ///< Channel number on which reception should be performed.
static bool m_dly_op_in_progress[RSCH_DLY_TS_NUM]; ///< Status of delayed operation.
/**
* Start delayed timeslot operation.
*
* @param[in] dly_ts_id Delayed timeslot ID.
*/
static void dly_op_start(rsch_dly_ts_id_t dly_ts_id)
{
assert(dly_ts_id < RSCH_DLY_TS_NUM);
m_dly_op_in_progress[dly_ts_id] = true;
}
/**
* Stop delayed timeslot operation.
*
* @param[in] dly_ts_id Delayed timeslot ID.
*/
static void dly_op_stop(rsch_dly_ts_id_t dly_ts_id)
{
assert(dly_ts_id < RSCH_DLY_TS_NUM);
m_dly_op_in_progress[dly_ts_id] = false;
}
/**
* Check if delayed operation is in progress.
*
* @retval true Delayed operation is in progress (waiting or ongoing).
* @retval false Delayed operation is not in progress.
*/
bool dly_op_is_in_progress(rsch_dly_ts_id_t dly_ts_id)
{
assert(dly_ts_id < RSCH_DLY_TS_NUM);
return m_dly_op_in_progress[dly_ts_id];
}
/**
* Notify MAC layer that requested timeslot is not granted if tx request failed.
*
* @param[in] result Result of TX request.
*/
static void notify_tx_timeslot_denied(bool result)
{
if (!result)
{
nrf_802154_notify_transmit_failed(mp_tx_psdu, NRF_802154_TX_ERROR_TIMESLOT_DENIED);
}
}
/**
* Notify MAC layer that requested timeslot is not granted if rx request failed.
*
* @param[in] result Result of RX request.
*/
static void notify_rx_timeslot_denied(bool result)
{
if (!result)
{
nrf_802154_notify_receive_failed(NRF_802154_RX_ERROR_DELAYED_TIMESLOT_DENIED);
}
}
/**
* Notify MAC layer that no frame was received before timeout.
*
* @param[in] p_context Not used.
*/
static void notify_rx_timeout(void * p_context)
{
(void)p_context;
dly_op_stop(RSCH_DLY_RX);
nrf_802154_notify_receive_failed(NRF_802154_RX_ERROR_DELAYED_TIMEOUT);
}
/**
* Handle TX timeslot start.
*/
static void nrf_802154_rsch_delayed_tx_timeslot_started(void)
{
bool result;
assert(dly_op_is_in_progress(RSCH_DLY_TX));
nrf_802154_pib_channel_set(m_tx_channel);
result = nrf_802154_request_channel_update();
if (result)
{
result = nrf_802154_request_transmit(NRF_802154_TERM_802154,
REQ_ORIG_DELAYED_TRX,
mp_tx_psdu,
m_tx_cca,
true,
notify_tx_timeslot_denied);
(void)result;
}
else
{
notify_tx_timeslot_denied(result);
}
dly_op_stop(RSCH_DLY_TX);
}
/**
* Handle RX timeslot start.
*/
static void nrf_802154_rsch_delayed_rx_timeslot_started(void)
{
bool result;
assert(dly_op_is_in_progress(RSCH_DLY_RX));
nrf_802154_pib_channel_set(m_rx_channel);
result = nrf_802154_request_channel_update();
if (result)
{
result = nrf_802154_request_receive(NRF_802154_TERM_802154,
REQ_ORIG_DELAYED_TRX,
notify_rx_timeslot_denied,
true);
if (result)
{
m_timeout_timer.t0 = nrf_802154_timer_sched_time_get();
nrf_802154_timer_sched_add(&m_timeout_timer, true);
}
else
{
dly_op_stop(RSCH_DLY_RX);
}
}
else
{
notify_rx_timeslot_denied(result);
dly_op_stop(RSCH_DLY_RX);
}
}
bool nrf_802154_delayed_trx_transmit(const uint8_t * p_data,
bool cca,
uint32_t t0,
uint32_t dt,
uint8_t channel)
{
bool result = true;
uint16_t timeslot_length;
if (dly_op_is_in_progress(RSCH_DLY_TX))
{
result = false;
}
if (result)
{
dt -= TX_SETUP_TIME;
dt -= TX_RAMP_UP_TIME;
if (cca)
{
dt -= nrf_802154_cca_before_tx_duration_get();
}
mp_tx_psdu = p_data;
m_tx_cca = cca;
m_tx_channel = channel;
timeslot_length = nrf_802154_tx_duration_get(p_data[0],
cca,
p_data[ACK_REQUEST_OFFSET] & ACK_REQUEST_BIT);
dly_op_start(RSCH_DLY_TX);
result = nrf_802154_rsch_delayed_timeslot_request(t0,
dt,
timeslot_length,
RSCH_PRIO_MAX,
RSCH_DLY_TX);
if (!result)
{
notify_tx_timeslot_denied(result);
dly_op_stop(RSCH_DLY_TX);
}
}
return result;
}
bool nrf_802154_delayed_trx_receive(uint32_t t0,
uint32_t dt,
uint32_t timeout,
uint8_t channel)
{
bool result;
result = !dly_op_is_in_progress(RSCH_DLY_RX);
if (result)
{
dt -= RX_SETUP_TIME;
dt -= RX_RAMP_UP_TIME;
dly_op_start(RSCH_DLY_RX);
result = nrf_802154_rsch_delayed_timeslot_request(t0,
dt,
timeout +
nrf_802154_rx_duration_get(MAX_PACKET_SIZE,
true),
RSCH_PRIO_MAX,
RSCH_DLY_RX);
if (result)
{
m_timeout_timer.dt = timeout;
m_timeout_timer.callback = notify_rx_timeout;
m_timeout_timer.p_context = NULL;
m_rx_channel = channel;
}
else
{
notify_rx_timeslot_denied(result);
dly_op_stop(RSCH_DLY_RX);
}
}
return result;
}
void nrf_802154_rsch_delayed_timeslot_started(rsch_dly_ts_id_t dly_ts_id)
{
switch (dly_ts_id)
{
case RSCH_DLY_TX:
nrf_802154_rsch_delayed_tx_timeslot_started();
break;
case RSCH_DLY_RX:
nrf_802154_rsch_delayed_rx_timeslot_started();
break;
default:
assert(false);
}
}
void nrf_802154_rsch_delayed_timeslot_failed(rsch_dly_ts_id_t dly_ts_id)
{
assert(dly_ts_id < RSCH_DLY_TS_NUM);
assert(dly_op_is_in_progress(dly_ts_id));
if (RSCH_DLY_TX == dly_ts_id)
{
notify_tx_timeslot_denied(false);
}
else
{
notify_rx_timeslot_denied(false);
}
dly_op_stop(dly_ts_id);
}
bool nrf_802154_delayed_trx_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig)
{
bool result = true;
if (!dly_op_is_in_progress(RSCH_DLY_RX))
{
// No active procedures, just return true.
}
else if ((REQ_ORIG_HIGHER_LAYER == req_orig) || (term_lvl >= NRF_802154_TERM_802154))
{
nrf_802154_timer_sched_remove(&m_timeout_timer);
dly_op_stop(RSCH_DLY_RX);
}
else
{
result = false;
}
return result;
}
void nrf_802154_delayed_trx_rx_started_hook(void)
{
if (dly_op_is_in_progress(RSCH_DLY_RX))
{
if (nrf_802154_timer_sched_remaining_time_get(&m_timeout_timer)
< nrf_802154_rx_duration_get(MAX_PACKET_SIZE, true))
{
m_timeout_timer.t0 = nrf_802154_timer_sched_time_get();
m_timeout_timer.dt = nrf_802154_rx_duration_get(MAX_PACKET_SIZE, true);
nrf_802154_timer_sched_add(&m_timeout_timer, true);
}
}
}

View file

@ -1,118 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_DELAYED_TRX_H__
#define NRF_802154_DELAYED_TRX_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_const.h"
#include "nrf_802154_types.h"
/**
* @defgroup nrf_802154_delayed_trx Delayed transmission and reception window features.
* @{
* @ingroup nrf_802154
* @brief Delayed transmission or receive window.
*
* This module implements delayed transmission and receive window features used in CSL and TSCH
* modes.
*/
/**
* @brief Request transmission of a frame at given time.
*
* If requested transmission is successful and the frame is transmitted the
* @ref nrf_802154_tx_started is called. If the requested frame cannot be transmitted at given time
* the @ref nrf_802154_transmit_failed function is called.
*
* @note Delayed transmission does not timeout waiting for ACK automatically. Waiting for ACK shall
* be timed out by the next higher layer or the ACK timeout module. The ACK timeout timer
* shall start when the @ref nrf_802154_tx_started function is called.
*
* @param[in] p_data Pointer to array containing data to transmit (PHR + PSDU).
* @param[in] cca If the driver should perform CCA procedure before transmission.
* @param[in] t0 Base of delay time [us].
* @param[in] dt Delta of delay time from @p t0 [us].
* @param[in] channel Number of channel on which the frame should be transmitted.
*/
bool nrf_802154_delayed_trx_transmit(const uint8_t * p_data,
bool cca,
uint32_t t0,
uint32_t dt,
uint8_t channel);
/**
*@}
**/
/**
* @brief Request reception of a frame at given time.
*
* If the requested is accepted and a frame is received during defined time slot
* @ref nrf_802154_received is called. If the request is rejected due to denied timeslot request
* or reception timeout expired the @ref nrf_802154_receive_failed function is called.
*
* @param[in] t0 Base of delay time [us].
* @param[in] dt Delta of delay time from @p t0 [us].
* @param[in] timeout Reception timeout (counted from @p t0 + @p dt) [us].
* @param[in] channel Number of channel on which the frame should be received.
*/
bool nrf_802154_delayed_trx_receive(uint32_t t0,
uint32_t dt,
uint32_t timeout,
uint8_t channel);
/**
* @brief Abort started delayed transmit/receive procedure.
*
* @param[in] term_lvl Termination level set by request aborting ongoing operation.
* @param[in] req_orig Module that originates this request.
*
* If delayed transmit/receive procedure are not running during call, this function does nothing.
*
* @retval true transmit/receive procedures have been stopped.
*/
bool nrf_802154_delayed_trx_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig);
/**
* @brief Extends timeout timer when reception start is detected and there is not enough time
* left for delayed RX operation.
*
* If delayed transmit/receive procedure are not running during call, this function does nothing.
*/
void nrf_802154_delayed_trx_rx_started_hook(void);
/**
*@}
**/
#endif // NRF_802154_DELAYED_TRX_H__

View file

@ -1,453 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements incoming frame filtering according to 3 and 4 levels of filtering.
*
* Filtering details are specified in 802.15.4-2015: 6.7.2.
* 1st and 2nd filtering level is performed by FSM module depending on promiscuous mode, when FCS is
* received.
*/
#include "nrf_802154_filter.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "nrf_802154_const.h"
#include "nrf_802154_pib.h"
#define FCF_CHECK_OFFSET (PHR_SIZE + FCF_SIZE)
#define SHORT_ADDR_CHECK_OFFSET (DEST_ADDR_OFFSET + SHORT_ADDRESS_SIZE)
#define EXTENDED_ADDR_CHECK_OFFSET (DEST_ADDR_OFFSET + EXTENDED_ADDRESS_SIZE)
/**
* @brief Check if given frame version is allowed for given frame type.
*
* @param[in] frame_type Type of incoming frame.
* @param[in] frame_version Version of incoming frame.
*
* @retval true Given frame version is allowed for given frame type.
* @retval false Given frame version is not allowed for given frame type.
*/
static bool frame_type_and_version_filter(uint8_t frame_type, uint8_t frame_version)
{
bool result;
switch (frame_type)
{
case FRAME_TYPE_BEACON:
case FRAME_TYPE_DATA:
case FRAME_TYPE_ACK:
case FRAME_TYPE_COMMAND:
result = (frame_version != FRAME_VERSION_3);
break;
case FRAME_TYPE_MULTIPURPOSE:
result = (frame_version == FRAME_VERSION_0);
break;
case FRAME_TYPE_FRAGMENT:
case FRAME_TYPE_EXTENDED:
result = true;
break;
default:
result = false;
}
return result;
}
/**
* @brief Check if given frame type may include destination address fields.
*
* @note Actual presence of destination address fields in the frame is indicated by FCF.
*
* @param[in] frame_type Type of incoming frame.
*
* @retval true Given frame type may include addressing fields.
* @retval false Given frame type may not include addressing fields.
*/
static bool dst_addressing_may_be_present(uint8_t frame_type)
{
bool result;
switch (frame_type)
{
case FRAME_TYPE_BEACON:
case FRAME_TYPE_DATA:
case FRAME_TYPE_ACK:
case FRAME_TYPE_COMMAND:
case FRAME_TYPE_MULTIPURPOSE:
result = true;
break;
case FRAME_TYPE_FRAGMENT:
case FRAME_TYPE_EXTENDED:
result = false;
break;
default:
result = false;
}
return result;
}
/**
* @brief Get offset of end of addressing fields for given frame assuming its version is 2006.
*
* If given frame contains errors that prevent getting offset, this function returns false. If there
* are no destination address fields in given frame, this function returns true and does not modify
* @p p_num_bytes. If there is destination address in given frame, this function returns true and
* inserts offset of addressing fields end to @p p_num_bytes.
*
* @param[in] p_psdu Pointer of PSDU of incoming frame.
* @param[out] p_num_bytes Offset of addressing fields end.
* @param[in] frame_type Type of incoming frame.
*
* @retval NRF_802154_RX_ERROR_NONE No errors in given frame were detected - it may be
* further processed.
* @retval NRF_802154_RX_ERROR_INVALID_DEST_ADDR The frame is valid but addressed to another node.
* @retval NRF_802154_RX_ERROR_INVALID_FRAME Detected an error in given frame - it should be
* discarded.
*/
static nrf_802154_rx_error_t dst_addressing_end_offset_get_2006(const uint8_t * p_psdu,
uint8_t * p_num_bytes,
uint8_t frame_type)
{
nrf_802154_rx_error_t result;
switch (p_psdu[DEST_ADDR_TYPE_OFFSET] & DEST_ADDR_TYPE_MASK)
{
case DEST_ADDR_TYPE_SHORT:
*p_num_bytes = SHORT_ADDR_CHECK_OFFSET;
result = NRF_802154_RX_ERROR_NONE;
break;
case DEST_ADDR_TYPE_EXTENDED:
*p_num_bytes = EXTENDED_ADDR_CHECK_OFFSET;
result = NRF_802154_RX_ERROR_NONE;
break;
case DEST_ADDR_TYPE_NONE:
if (nrf_802154_pib_pan_coord_get() || (frame_type == FRAME_TYPE_BEACON))
{
switch (p_psdu[SRC_ADDR_TYPE_OFFSET] & SRC_ADDR_TYPE_MASK)
{
case SRC_ADDR_TYPE_SHORT:
*p_num_bytes = SHORT_ADDR_CHECK_OFFSET;
result = NRF_802154_RX_ERROR_NONE;
break;
case SRC_ADDR_TYPE_EXTENDED:
*p_num_bytes = EXTENDED_ADDR_CHECK_OFFSET;
result = NRF_802154_RX_ERROR_NONE;
break;
default:
result = NRF_802154_RX_ERROR_INVALID_FRAME;
}
}
else
{
result = NRF_802154_RX_ERROR_INVALID_DEST_ADDR;
}
break;
default:
result = NRF_802154_RX_ERROR_INVALID_FRAME;
}
return result;
}
/**
* @brief Get offset of end of addressing fields for given frame assuming its version is 2015.
*
* If given frame contains errors that prevent getting offset, this function returns false. If there
* are no destination address fields in given frame, this function returns true and does not modify
* @p p_num_bytes. If there is destination address in given frame, this function returns true and
* inserts offset of addressing fields end to @p p_num_bytes.
*
* @param[in] p_psdu Pointer of PSDU of incoming frame.
* @param[out] p_num_bytes Offset of addressing fields end.
* @param[in] frame_type Type of incoming frame.
*
* @retval NRF_802154_RX_ERROR_NONE No errors in given frame were detected - it may be
* further processed.
* @retval NRF_802154_RX_ERROR_INVALID_DEST_ADDR The frame is valid but addressed to another node.
* @retval NRF_802154_RX_ERROR_INVALID_FRAME Detected an error in given frame - it should be
* discarded.
*/
static nrf_802154_rx_error_t dst_addressing_end_offset_get_2015(const uint8_t * p_psdu,
uint8_t * p_num_bytes,
uint8_t frame_type)
{
nrf_802154_rx_error_t result;
switch (frame_type)
{
case FRAME_TYPE_BEACON:
case FRAME_TYPE_DATA:
case FRAME_TYPE_ACK:
case FRAME_TYPE_COMMAND:
// TODO: Implement dst addressing filtering according to 2015 spec
result = dst_addressing_end_offset_get_2006(p_psdu, p_num_bytes, frame_type);
break;
case FRAME_TYPE_MULTIPURPOSE:
// TODO: Implement dst addressing filtering according to 2015 spec
result = NRF_802154_RX_ERROR_INVALID_FRAME;
break;
case FRAME_TYPE_FRAGMENT:
case FRAME_TYPE_EXTENDED:
// No addressing data
result = NRF_802154_RX_ERROR_NONE;
break;
default:
result = NRF_802154_RX_ERROR_INVALID_FRAME;
}
return result;
}
/**
* @brief Get offset of end of addressing fields for given frame.
*
* If given frame contains errors that prevent getting offset, this function returns false. If there
* are no destination address fields in given frame, this function returns true and does not modify
* @p p_num_bytes. If there is destination address in given frame, this function returns true and
* inserts offset of addressing fields end to @p p_num_bytes.
*
* @param[in] p_psdu Pointer of PSDU of incoming frame.
* @param[out] p_num_bytes Offset of addressing fields end.
* @param[in] frame_type Type of incoming frame.
*
* @retval NRF_802154_RX_ERROR_NONE No errors in given frame were detected - it may be
* further processed.
* @retval NRF_802154_RX_ERROR_INVALID_DEST_ADDR The frame is valid but addressed to another node.
* @retval NRF_802154_RX_ERROR_INVALID_FRAME Detected an error in given frame - it should be
* discarded.
*/
static nrf_802154_rx_error_t dst_addressing_end_offset_get(const uint8_t * p_psdu,
uint8_t * p_num_bytes,
uint8_t frame_type,
uint8_t frame_version)
{
nrf_802154_rx_error_t result;
switch (frame_version)
{
case FRAME_VERSION_0:
case FRAME_VERSION_1:
result = dst_addressing_end_offset_get_2006(p_psdu, p_num_bytes, frame_type);
break;
case FRAME_VERSION_2:
result = dst_addressing_end_offset_get_2015(p_psdu, p_num_bytes, frame_type);
break;
default:
result = NRF_802154_RX_ERROR_INVALID_FRAME;
}
return result;
}
/**
* Verify if destination PAN Id of incoming frame allows processing by this node.
*
* @param[in] p_psdu Pointer of PSDU of incoming frame.
*
* @retval true PAN Id of incoming frame allows further processing of the frame.
* @retval false PAN Id of incoming frame does not allow further processing.
*/
static bool dst_pan_id_check(const uint8_t * p_psdu)
{
bool result;
if ((0 == memcmp(&p_psdu[PAN_ID_OFFSET], nrf_802154_pib_pan_id_get(), PAN_ID_SIZE)) ||
(0 == memcmp(&p_psdu[PAN_ID_OFFSET], BROADCAST_ADDRESS, PAN_ID_SIZE)))
{
result = true;
}
else if ((FRAME_TYPE_BEACON == (p_psdu[FRAME_TYPE_OFFSET] & FRAME_TYPE_MASK)) &&
(0 == memcmp(nrf_802154_pib_pan_id_get(), BROADCAST_ADDRESS, PAN_ID_SIZE)))
{
result = true;
}
else
{
result = false;
}
return result;
}
/**
* Verify if destination short address of incoming frame allows processing by this node.
*
* @param[in] p_psdu Pointer of PSDU of incoming frame.
*
* @retval true Destination address of incoming frame allows further processing of the frame.
* @retval false Destination address of incoming frame does not allow further processing.
*/
static bool dst_short_addr_check(const uint8_t * p_psdu)
{
bool result;
if ((0 == memcmp(&p_psdu[DEST_ADDR_OFFSET],
nrf_802154_pib_short_address_get(),
SHORT_ADDRESS_SIZE)) ||
(0 == memcmp(&p_psdu[DEST_ADDR_OFFSET], BROADCAST_ADDRESS, SHORT_ADDRESS_SIZE)))
{
result = true;
}
else if (FRAME_TYPE_BEACON == (p_psdu[FRAME_TYPE_OFFSET] & FRAME_TYPE_MASK))
{
result = true;
}
else if (DEST_ADDR_TYPE_NONE == (p_psdu[DEST_ADDR_TYPE_OFFSET] & DEST_ADDR_TYPE_MASK) &&
nrf_802154_pib_pan_coord_get())
{
result = true;
}
else
{
result = false;
}
return result;
}
/**
* Verify if destination extended address of incoming frame allows processing by this node.
*
* @param[in] p_psdu Pointer of PSDU of incoming frame.
*
* @retval true Destination address of incoming frame allows further processing of the frame.
* @retval false Destination address of incoming frame does not allow further processing.
*/
static bool dst_extended_addr_check(const uint8_t * p_psdu)
{
bool result;
if (0 == memcmp(&p_psdu[DEST_ADDR_OFFSET],
nrf_802154_pib_extended_address_get(),
EXTENDED_ADDRESS_SIZE))
{
result = true;
}
else if (FRAME_TYPE_BEACON == (p_psdu[FRAME_TYPE_OFFSET] & FRAME_TYPE_MASK))
{
result = true;
}
else if (DEST_ADDR_TYPE_NONE == (p_psdu[DEST_ADDR_TYPE_OFFSET] & DEST_ADDR_TYPE_MASK) &&
nrf_802154_pib_pan_coord_get())
{
result = true;
}
else
{
result = false;
}
return result;
}
nrf_802154_rx_error_t nrf_802154_filter_frame_part(const uint8_t * p_psdu, uint8_t * p_num_bytes)
{
nrf_802154_rx_error_t result = NRF_802154_RX_ERROR_INVALID_FRAME;
switch (*p_num_bytes)
{
case FCF_CHECK_OFFSET:
{
if (p_psdu[0] < IMM_ACK_LENGTH || p_psdu[0] > MAX_PACKET_SIZE)
{
result = NRF_802154_RX_ERROR_INVALID_LENGTH;
break;
}
uint8_t frame_type = p_psdu[FRAME_TYPE_OFFSET] & FRAME_TYPE_MASK;
uint8_t frame_version = p_psdu[FRAME_VERSION_OFFSET] & FRAME_VERSION_MASK;
if (!frame_type_and_version_filter(frame_type, frame_version))
{
result = NRF_802154_RX_ERROR_INVALID_FRAME;
break;
}
if (!dst_addressing_may_be_present(frame_type))
{
result = NRF_802154_RX_ERROR_NONE;
break;
}
result = dst_addressing_end_offset_get(p_psdu, p_num_bytes, frame_type, frame_version);
break;
}
case SHORT_ADDR_CHECK_OFFSET:
if (!dst_pan_id_check(p_psdu))
{
result = NRF_802154_RX_ERROR_INVALID_DEST_ADDR;
break;
}
result = dst_short_addr_check(p_psdu) ? NRF_802154_RX_ERROR_NONE :
NRF_802154_RX_ERROR_INVALID_DEST_ADDR;
break;
case EXTENDED_ADDR_CHECK_OFFSET:
if (!dst_pan_id_check(p_psdu))
{
result = NRF_802154_RX_ERROR_INVALID_DEST_ADDR;
break;
}
result = dst_extended_addr_check(p_psdu) ? NRF_802154_RX_ERROR_NONE :
NRF_802154_RX_ERROR_INVALID_DEST_ADDR;
break;
default:
assert(false);
}
return result;
}

View file

@ -1,76 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This file implements incoming frame filter API.
*
*/
#ifndef NRF_802154_FILTER_H_
#define NRF_802154_FILTER_H_
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_types.h"
/**
* @defgroup nrf_802154_filter Incoming frame filter API.
* @{
* @ingroup nrf_802154
* @brief Procedures used to discard incoming frames that contain unexpected data in PHR or MHR.
*/
/**
* @brief Verify if given part of the frame is valid.
*
* This function is called a few times for each received frame. First call is after FCF is received
* (PSDU length is 1 - @p p_num_bytes value is 1). Subsequent calls are performed when number of
* bytes requested by previous call is available. Iteration ends when function does not request
* any more bytes to check.
* If verified part of the function is correct this function returns true and sets @p p_num_bytes to
* number of bytes that should be available in PSDU during next iteration. If frame is correct and
* there is nothing more to check, function returns true and does not modify @p p_num_bytes value.
* If verified frame is incorrect this function returns false and @p p_num_bytes value is undefined.
*
* @param[in] p_psdu Pointer to PSDU of incoming frame.
* @param[inout] p_num_bytes Number of bytes available in @p p_psdu buffer. This value is set to
* requested number of bytes for next iteration or this value is
* unchanged if no more iterations shall be performed during filtering of
* given frame.
*
* @retval NRF_802154_RX_ERROR_NONE Verified part of the incoming frame is valid.
* @retval NRF_802154_RX_ERROR_INVALID_FRAME Verified part of the incoming frame is invalid.
* @retval NRF_802154_RX_ERROR_INVALID_DEST_ADDR Incoming frame has destination address that
* mismatches address of this node.
*/
nrf_802154_rx_error_t nrf_802154_filter_frame_part(const uint8_t * p_psdu, uint8_t * p_num_bytes);
#endif /* NRF_802154_FILTER_H_ */

View file

@ -1,171 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements ACK timeout procedure for the 802.15.4 driver.
*
*/
#include "nrf_802154_ack_timeout.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_notification.h"
#include "nrf_802154_procedures_duration.h"
#include "nrf_802154_request.h"
#include "timer_scheduler/nrf_802154_timer_sched.h"
#define RETRY_DELAY 500 ///< Procedure is delayed by this time if it cannot be performed at the moment [us].
#define MAX_RETRY_DELAY 1000000 ///< Maximum allowed delay of procedure retry [us].
static void timeout_timer_retry(void);
static uint32_t m_timeout = NRF_802154_PRECISE_ACK_TIMEOUT_DEFAULT_TIMEOUT; ///< ACK timeout in us.
static nrf_802154_timer_t m_timer; ///< Timer used to notify when the ACK frama is not received for too long.
static volatile bool m_procedure_is_active;
static const uint8_t * mp_frame;
static void notify_tx_error(bool result)
{
if (result)
{
nrf_802154_notify_transmit_failed(mp_frame, NRF_802154_TX_ERROR_NO_ACK);
}
}
static void timeout_timer_fired(void * p_context)
{
(void)p_context;
if (m_procedure_is_active)
{
if (nrf_802154_request_receive(NRF_802154_TERM_802154,
REQ_ORIG_ACK_TIMEOUT,
notify_tx_error,
false))
{
m_procedure_is_active = false;
}
else
{
timeout_timer_retry();
}
}
}
static void timeout_timer_retry(void)
{
m_timer.dt += RETRY_DELAY;
assert(m_timer.dt <= MAX_RETRY_DELAY);
nrf_802154_timer_sched_add(&m_timer, true);
}
static void timeout_timer_start(void)
{
m_timer.callback = timeout_timer_fired;
m_timer.p_context = NULL;
m_timer.t0 = nrf_802154_timer_sched_time_get();
m_timer.dt = m_timeout +
IMM_ACK_DURATION +
nrf_802154_frame_duration_get(mp_frame[0], false, true);
m_procedure_is_active = true;
nrf_802154_timer_sched_add(&m_timer, true);
}
static void timeout_timer_stop(void)
{
m_procedure_is_active = false;
// To make sure `timeout_timer_fired()` detects that procedure is being stopped if it preempts
// this function.
__DMB();
nrf_802154_timer_sched_remove(&m_timer);
}
void nrf_802154_ack_timeout_time_set(uint32_t time)
{
m_timeout = time;
}
bool nrf_802154_ack_timeout_tx_started_hook(const uint8_t * p_frame)
{
mp_frame = p_frame;
timeout_timer_start();
return true;
}
bool nrf_802154_ack_timeout_abort(nrf_802154_term_t term_lvl, req_originator_t req_orig)
{
bool result;
if (!m_procedure_is_active || req_orig == REQ_ORIG_ACK_TIMEOUT)
{
// Ignore if procedure is not running or self-request.
result = true;
}
else if (term_lvl >= NRF_802154_TERM_802154)
{
// Stop procedure only if termination level is high enough.
timeout_timer_stop();
result = true;
}
else
{
result = false;
}
return result;
}
void nrf_802154_ack_timeout_transmitted_hook(const uint8_t * p_frame)
{
assert((p_frame == mp_frame) || (!m_procedure_is_active));
timeout_timer_stop();
}
bool nrf_802154_ack_timeout_tx_failed_hook(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
(void)error;
assert((p_frame == mp_frame) || (!m_procedure_is_active));
timeout_timer_stop();
return true;
}

View file

@ -1,753 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 radio driver.
*
*/
#include "nrf_802154.h"
#include <assert.h>
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#include <string.h>
#include "nrf_802154_ack_pending_bit.h"
#include "nrf_802154_config.h"
#include "nrf_802154_const.h"
#include "nrf_802154_core.h"
#include "nrf_802154_critical_section.h"
#include "nrf_802154_debug.h"
#include "nrf_802154_notification.h"
#include "nrf_802154_pib.h"
#include "nrf_802154_priority_drop.h"
#include "nrf_802154_request.h"
#include "nrf_802154_revision.h"
#include "nrf_802154_rsch.h"
#include "nrf_802154_rsch_crit_sect.h"
#include "nrf_802154_rssi.h"
#include "nrf_802154_rx_buffer.h"
#include "nrf_802154_timer_coord.h"
#include "hal/nrf_radio.h"
#include "platform/clock/nrf_802154_clock.h"
#include "platform/lp_timer/nrf_802154_lp_timer.h"
#include "platform/temperature/nrf_802154_temperature.h"
#include "timer_scheduler/nrf_802154_timer_sched.h"
#include "mac_features/nrf_802154_ack_timeout.h"
#include "mac_features/nrf_802154_csma_ca.h"
#include "mac_features/nrf_802154_delayed_trx.h"
#if ENABLE_FEM
#include "fem/nrf_fem_control_api.h"
#endif
#define RAW_LENGTH_OFFSET 0
#define RAW_PAYLOAD_OFFSET 1
#if !NRF_802154_USE_RAW_API
/** Static transmit buffer used by @sa nrf_802154_transmit() family of functions.
*
* If none of functions using this buffer is called and link time optimization is enabled, this
* buffer should be removed by linker.
*/
static uint8_t m_tx_buffer[RAW_PAYLOAD_OFFSET + MAX_PACKET_SIZE];
/**
* @brief Fill transmit buffer with given data.
*
* @param[in] p_data Pointer to array containing payload of a data to transmit. The array
* should exclude PHR or FCS fields of 802.15.4 frame.
* @param[in] length Length of given frame. This value shall exclude PHR and FCS fields from
* the given frame (exact size of buffer pointed by @p p_data).
*/
static void tx_buffer_fill(const uint8_t * p_data, uint8_t length)
{
assert(length <= MAX_PACKET_SIZE - FCS_SIZE);
m_tx_buffer[RAW_LENGTH_OFFSET] = length + FCS_SIZE;
memcpy(&m_tx_buffer[RAW_PAYLOAD_OFFSET], p_data, length);
}
#endif // !NRF_802154_USE_RAW_API
/**
* @brief Get timestamp of the last received frame.
*
* @note This function increments the returned value by 1 us if the timestamp is equal to the
* @ref NRF_802154_NO_TIMESTAMP value to indicate that the timestamp is available.
*
* @returns Timestamp [us] of the last received frame or @ref NRF_802154_NO_TIMESTAMP if
* the timestamp is inaccurate.
*/
static uint32_t last_rx_frame_timestamp_get(void)
{
#if NRF_802154_FRAME_TIMESTAMP_ENABLED
uint32_t timestamp;
bool timestamp_received = nrf_802154_timer_coord_timestamp_get(&timestamp);
if (!timestamp_received)
{
timestamp = NRF_802154_NO_TIMESTAMP;
}
else
{
if (timestamp == NRF_802154_NO_TIMESTAMP)
{
timestamp++;
}
}
return timestamp;
#else // NRF_802154_FRAME_TIMESTAMP_ENABLED
return NRF_802154_NO_TIMESTAMP;
#endif // NRF_802154_FRAME_TIMESTAMP_ENABLED
}
void nrf_802154_channel_set(uint8_t channel)
{
bool changed = nrf_802154_pib_channel_get() != channel;
nrf_802154_pib_channel_set(channel);
if (changed)
{
nrf_802154_request_channel_update();
}
}
uint8_t nrf_802154_channel_get(void)
{
return nrf_802154_pib_channel_get();
}
void nrf_802154_tx_power_set(int8_t power)
{
nrf_802154_pib_tx_power_set(power);
}
int8_t nrf_802154_tx_power_get(void)
{
return nrf_802154_pib_tx_power_get();
}
void nrf_802154_temperature_changed(void)
{
nrf_802154_request_cca_cfg_update();
}
void nrf_802154_pan_id_set(const uint8_t * p_pan_id)
{
nrf_802154_pib_pan_id_set(p_pan_id);
}
void nrf_802154_extended_address_set(const uint8_t * p_extended_address)
{
nrf_802154_pib_extended_address_set(p_extended_address);
}
void nrf_802154_short_address_set(const uint8_t * p_short_address)
{
nrf_802154_pib_short_address_set(p_short_address);
}
int8_t nrf_802154_dbm_from_energy_level_calculate(uint8_t energy_level)
{
return ED_MIN_DBM + (energy_level / ED_RESULT_FACTOR);
}
uint8_t nrf_802154_ccaedthres_from_dbm_calculate(int8_t dbm)
{
return dbm - ED_MIN_DBM;
}
uint32_t nrf_802154_first_symbol_timestamp_get(uint32_t end_timestamp, uint8_t psdu_length)
{
uint32_t frame_symbols = PHY_SHR_SYMBOLS;
frame_symbols += (PHR_SIZE + psdu_length) * PHY_SYMBOLS_PER_OCTET;
return end_timestamp - (frame_symbols * PHY_US_PER_SYMBOL);
}
void nrf_802154_init(void)
{
nrf_802154_ack_pending_bit_init();
nrf_802154_core_init();
nrf_802154_clock_init();
nrf_802154_critical_section_init();
nrf_802154_debug_init();
nrf_802154_notification_init();
nrf_802154_lp_timer_init();
nrf_802154_pib_init();
nrf_802154_priority_drop_init();
nrf_802154_request_init();
nrf_802154_revision_init();
nrf_802154_rsch_crit_sect_init();
nrf_802154_rsch_init();
nrf_802154_rx_buffer_init();
nrf_802154_temperature_init();
nrf_802154_timer_coord_init();
nrf_802154_timer_sched_init();
}
void nrf_802154_deinit(void)
{
nrf_802154_timer_sched_deinit();
nrf_802154_timer_coord_uninit();
nrf_802154_temperature_deinit();
nrf_802154_rsch_uninit();
nrf_802154_lp_timer_deinit();
nrf_802154_clock_deinit();
nrf_802154_core_deinit();
}
#if !NRF_802154_INTERNAL_RADIO_IRQ_HANDLING
void nrf_802154_radio_irq_handler(void)
{
nrf_802154_core_irq_handler();
}
#endif // !NRF_802154_INTERNAL_RADIO_IRQ_HANDLING
#if ENABLE_FEM
void nrf_802154_fem_control_cfg_set(const nrf_802154_fem_control_cfg_t * p_cfg)
{
nrf_fem_control_cfg_set(p_cfg);
}
void nrf_802154_fem_control_cfg_get(nrf_802154_fem_control_cfg_t * p_cfg)
{
nrf_fem_control_cfg_get(p_cfg);
}
#endif // ENABLE_FEM
nrf_802154_state_t nrf_802154_state_get(void)
{
switch (nrf_802154_core_state_get())
{
case RADIO_STATE_SLEEP:
case RADIO_STATE_FALLING_ASLEEP:
return NRF_802154_STATE_SLEEP;
case RADIO_STATE_RX:
case RADIO_STATE_TX_ACK:
return NRF_802154_STATE_RECEIVE;
case RADIO_STATE_CCA_TX:
case RADIO_STATE_TX:
case RADIO_STATE_RX_ACK:
return NRF_802154_STATE_TRANSMIT;
case RADIO_STATE_ED:
return NRF_802154_STATE_ENERGY_DETECTION;
case RADIO_STATE_CCA:
return NRF_802154_STATE_CCA;
case RADIO_STATE_CONTINUOUS_CARRIER:
return NRF_802154_STATE_CONTINUOUS_CARRIER;
}
return NRF_802154_STATE_INVALID;
}
bool nrf_802154_sleep(void)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_SLEEP);
result = nrf_802154_request_sleep(NRF_802154_TERM_802154);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_SLEEP);
return result;
}
nrf_802154_sleep_error_t nrf_802154_sleep_if_idle(void)
{
nrf_802154_sleep_error_t result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_SLEEP);
result =
nrf_802154_request_sleep(NRF_802154_TERM_NONE) ? NRF_802154_SLEEP_ERROR_NONE :
NRF_802154_SLEEP_ERROR_BUSY;
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_SLEEP);
return result;
}
bool nrf_802154_receive(void)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RECEIVE);
result = nrf_802154_request_receive(NRF_802154_TERM_802154, REQ_ORIG_HIGHER_LAYER, NULL, true);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RECEIVE);
return result;
}
#if NRF_802154_USE_RAW_API
bool nrf_802154_transmit_raw(const uint8_t * p_data, bool cca)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_TRANSMIT);
result = nrf_802154_request_transmit(NRF_802154_TERM_NONE,
REQ_ORIG_HIGHER_LAYER,
p_data,
cca,
false,
NULL);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_TRANSMIT);
return result;
}
#else // NRF_802154_USE_RAW_API
bool nrf_802154_transmit(const uint8_t * p_data, uint8_t length, bool cca)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_TRANSMIT);
tx_buffer_fill(p_data, length);
result = nrf_802154_request_transmit(NRF_802154_TERM_NONE,
REQ_ORIG_HIGHER_LAYER,
m_tx_buffer,
cca,
false,
NULL);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_TRANSMIT);
return result;
}
#endif // NRF_802154_USE_RAW_API
bool nrf_802154_transmit_raw_at(const uint8_t * p_data,
bool cca,
uint32_t t0,
uint32_t dt,
uint8_t channel)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_TRANSMIT_AT);
result = nrf_802154_delayed_trx_transmit(p_data, cca, t0, dt, channel);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_TRANSMIT_AT);
return result;
}
bool nrf_802154_receive_at(uint32_t t0,
uint32_t dt,
uint32_t timeout,
uint8_t channel)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RECEIVE_AT);
result = nrf_802154_delayed_trx_receive(t0, dt, timeout, channel);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RECEIVE_AT);
return result;
}
bool nrf_802154_energy_detection(uint32_t time_us)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_ENERGY_DETECTION);
result = nrf_802154_request_energy_detection(NRF_802154_TERM_NONE, time_us);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_ENERGY_DETECTION);
return result;
}
bool nrf_802154_cca(void)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CCA);
result = nrf_802154_request_cca(NRF_802154_TERM_NONE);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CCA);
return result;
}
bool nrf_802154_continuous_carrier(void)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CONTINUOUS_CARRIER);
result = nrf_802154_request_continuous_carrier(NRF_802154_TERM_NONE);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CONTINUOUS_CARRIER);
return result;
}
#if NRF_802154_USE_RAW_API
void nrf_802154_buffer_free_raw(uint8_t * p_data)
{
bool result;
rx_buffer_t * p_buffer = (rx_buffer_t *)p_data;
assert(p_buffer->free == false);
(void)p_buffer;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_BUFFER_FREE);
result = nrf_802154_request_buffer_free(p_data);
assert(result);
(void)result;
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_BUFFER_FREE);
}
bool nrf_802154_buffer_free_immediately_raw(uint8_t * p_data)
{
bool result;
rx_buffer_t * p_buffer = (rx_buffer_t *)p_data;
assert(p_buffer->free == false);
(void)p_buffer;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_BUFFER_FREE);
result = nrf_802154_request_buffer_free(p_data);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_BUFFER_FREE);
return result;
}
#else // NRF_802154_USE_RAW_API
void nrf_802154_buffer_free(uint8_t * p_data)
{
bool result;
rx_buffer_t * p_buffer = (rx_buffer_t *)(p_data - RAW_PAYLOAD_OFFSET);
assert(p_buffer->free == false);
(void)p_buffer;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_BUFFER_FREE);
result = nrf_802154_request_buffer_free(p_data - RAW_PAYLOAD_OFFSET);
assert(result);
(void)result;
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_BUFFER_FREE);
}
bool nrf_802154_buffer_free_immediately(uint8_t * p_data)
{
bool result;
rx_buffer_t * p_buffer = (rx_buffer_t *)(p_data - RAW_PAYLOAD_OFFSET);
assert(p_buffer->free == false);
(void)p_buffer;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_BUFFER_FREE);
result = nrf_802154_request_buffer_free(p_data - RAW_PAYLOAD_OFFSET);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_BUFFER_FREE);
return result;
}
#endif // NRF_802154_USE_RAW_API
int8_t nrf_802154_rssi_last_get(void)
{
uint8_t negative_dbm = nrf_radio_rssi_sample_get();
negative_dbm = nrf_802154_rssi_sample_corrected_get(negative_dbm);
return -(int8_t)negative_dbm;
}
bool nrf_802154_promiscuous_get(void)
{
return nrf_802154_pib_promiscuous_get();
}
void nrf_802154_promiscuous_set(bool enabled)
{
nrf_802154_pib_promiscuous_set(enabled);
}
void nrf_802154_auto_ack_set(bool enabled)
{
nrf_802154_pib_auto_ack_set(enabled);
}
bool nrf_802154_auto_ack_get(void)
{
return nrf_802154_pib_auto_ack_get();
}
bool nrf_802154_pan_coord_get(void)
{
return nrf_802154_pib_pan_coord_get();
}
void nrf_802154_pan_coord_set(bool enabled)
{
nrf_802154_pib_pan_coord_set(enabled);
}
void nrf_802154_auto_pending_bit_set(bool enabled)
{
nrf_802154_ack_pending_bit_set(enabled);
}
bool nrf_802154_pending_bit_for_addr_set(const uint8_t * p_addr, bool extended)
{
return nrf_802154_ack_pending_bit_for_addr_set(p_addr, extended);
}
bool nrf_802154_pending_bit_for_addr_clear(const uint8_t * p_addr, bool extended)
{
return nrf_802154_ack_pending_bit_for_addr_clear(p_addr, extended);
}
void nrf_802154_pending_bit_for_addr_reset(bool extended)
{
nrf_802154_ack_pending_bit_for_addr_reset(extended);
}
void nrf_802154_cca_cfg_set(const nrf_802154_cca_cfg_t * p_cca_cfg)
{
nrf_802154_pib_cca_cfg_set(p_cca_cfg);
nrf_802154_request_cca_cfg_update();
}
void nrf_802154_cca_cfg_get(nrf_802154_cca_cfg_t * p_cca_cfg)
{
nrf_802154_pib_cca_cfg_get(p_cca_cfg);
}
#if NRF_802154_CSMA_CA_ENABLED
#if NRF_802154_USE_RAW_API
void nrf_802154_transmit_csma_ca_raw(const uint8_t * p_data)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMACA);
nrf_802154_csma_ca_start(p_data);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMACA);
}
#else // NRF_802154_USE_RAW_API
void nrf_802154_transmit_csma_ca(const uint8_t * p_data, uint8_t length)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CSMACA);
tx_buffer_fill(p_data, length);
nrf_802154_csma_ca_start(m_tx_buffer);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CSMACA);
}
#endif // NRF_802154_USE_RAW_API
#endif // NRF_802154_CSMA_CA_ENABLED
#if NRF_802154_ACK_TIMEOUT_ENABLED
void nrf_802154_ack_timeout_set(uint32_t time)
{
nrf_802154_ack_timeout_time_set(time);
}
#endif // NRF_802154_ACK_TIMEOUT_ENABLED
__WEAK void nrf_802154_tx_ack_started(void)
{
// Intentionally empty
}
#if NRF_802154_USE_RAW_API
__WEAK void nrf_802154_received_raw(uint8_t * p_data, int8_t power, uint8_t lqi)
{
nrf_802154_received_timestamp_raw(p_data, power, lqi, last_rx_frame_timestamp_get());
}
__WEAK void nrf_802154_received_timestamp_raw(uint8_t * p_data,
int8_t power,
uint8_t lqi,
uint32_t time)
{
(void)power;
(void)lqi;
(void)time;
nrf_802154_buffer_free_raw(p_data);
}
#else // NRF_802154_USE_RAW_API
__WEAK void nrf_802154_received(uint8_t * p_data, uint8_t length, int8_t power, uint8_t lqi)
{
nrf_802154_received_timestamp(p_data, length, power, lqi, last_rx_frame_timestamp_get());
}
__WEAK void nrf_802154_received_timestamp(uint8_t * p_data,
uint8_t length,
int8_t power,
uint8_t lqi,
uint32_t time)
{
(void)length;
(void)power;
(void)lqi;
(void)time;
nrf_802154_buffer_free(p_data);
}
#endif // !NRF_802154_USE_RAW_API
__WEAK void nrf_802154_receive_failed(nrf_802154_rx_error_t error)
{
(void)error;
}
__WEAK void nrf_802154_tx_started(const uint8_t * p_frame)
{
(void)p_frame;
}
#if NRF_802154_USE_RAW_API
__WEAK void nrf_802154_transmitted_raw(const uint8_t * p_frame,
uint8_t * p_ack,
int8_t power,
uint8_t lqi)
{
uint32_t timestamp = (p_ack == NULL) ? NRF_802154_NO_TIMESTAMP : last_rx_frame_timestamp_get();
nrf_802154_transmitted_timestamp_raw(p_frame, p_ack, power, lqi, timestamp);
}
__WEAK void nrf_802154_transmitted_timestamp_raw(const uint8_t * p_frame,
uint8_t * p_ack,
int8_t power,
uint8_t lqi,
uint32_t time)
{
(void)p_frame;
(void)power;
(void)lqi;
(void)time;
if (p_ack != NULL)
{
nrf_802154_buffer_free_raw(p_ack);
}
}
#else // NRF_802154_USE_RAW_API
__WEAK void nrf_802154_transmitted(const uint8_t * p_frame,
uint8_t * p_ack,
uint8_t length,
int8_t power,
uint8_t lqi)
{
uint32_t timestamp = (p_ack == NULL) ? NRF_802154_NO_TIMESTAMP : last_rx_frame_timestamp_get();
nrf_802154_transmitted_timestamp(p_frame, p_ack, length, power, lqi, timestamp);
}
__WEAK void nrf_802154_transmitted_timestamp(const uint8_t * p_frame,
uint8_t * p_ack,
uint8_t length,
int8_t power,
uint8_t lqi,
uint32_t time)
{
(void)p_frame;
(void)length;
(void)power;
(void)lqi;
(void)time;
if (p_ack != NULL)
{
nrf_802154_buffer_free(p_ack);
}
}
#endif // NRF_802154_USE_RAW_API
__WEAK void nrf_802154_transmit_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
(void)p_frame;
(void)error;
}
__WEAK void nrf_802154_energy_detected(uint8_t result)
{
(void)result;
}
__WEAK void nrf_802154_energy_detection_failed(nrf_802154_ed_error_t error)
{
(void)error;
}
__WEAK void nrf_802154_cca_done(bool channel_free)
{
(void)channel_free;
}
__WEAK void nrf_802154_cca_failed(nrf_802154_cca_error_t error)
{
(void)error;
}

File diff suppressed because it is too large Load diff

View file

@ -1,420 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements procedures to set pending bit in nRF 802.15.4 radio driver.
*
*/
#include "nrf_802154_ack_pending_bit.h"
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "nrf_802154_config.h"
#include "nrf_802154_const.h"
#include "hal/nrf_radio.h"
/// Maximum number of Short Addresses of nodes for which there is pending data in buffer.
#define NUM_PENDING_SHORT_ADDRESSES NRF_802154_PENDING_SHORT_ADDRESSES
/// Maximum number of Extended Addresses of nodes for which there is pending data in buffer.
#define NUM_PENDING_EXTENDED_ADDRESSES NRF_802154_PENDING_EXTENDED_ADDRESSES
/// Value used to mark Short Address as unused.
#define UNUSED_PENDING_SHORT_ADDRESS ((uint8_t[SHORT_ADDRESS_SIZE]) {0xff, 0xff})
/// Value used to mark Extended Address as unused.
#define UNUSED_PENDING_EXTENDED_ADDRESS ((uint8_t[EXTENDED_ADDRESS_SIZE]) {0})
/// If pending bit in ACK frame should be set to valid or default value.
static bool m_setting_pending_bit_enabled;
/// Array of Short Addresses of nodes for which there is pending data in the buffer.
static uint8_t m_pending_short[NUM_PENDING_SHORT_ADDRESSES][SHORT_ADDRESS_SIZE];
/// Array of Extended Addresses of nodes for which there is pending data in the buffer.
static uint8_t m_pending_extended[NUM_PENDING_EXTENDED_ADDRESSES][EXTENDED_ADDRESS_SIZE];
/// Current number of Short Addresses of nodes for which there is pending data in the buffer.
static uint8_t m_num_of_pending_short;
/// Current number of Extended Addresses of nodes for which there is pending data in the buffer.
static uint8_t m_num_of_pending_extended;
/**
* @brief Compare two extended addresses.
*
* @param[in] p_first_addr Pointer to a first address that should be compared.
* @param[in] p_second_addr Pointer to a second address that should be compared.
*
* @retval -1 First address is less than the second address.
* @retval 0 First address is equal to the second address.
* @retval 1 First address is greater than the second address.
*/
static int8_t extended_addr_compare(const uint8_t * p_first_addr, const uint8_t * p_second_addr)
{
uint32_t first_addr;
uint32_t second_addr;
// Compare extended address in two steps to prevent unaligned access error.
for (uint32_t i = 0; i < EXTENDED_ADDRESS_SIZE / sizeof(uint32_t); i++)
{
first_addr = *(uint32_t *)(p_first_addr + (i * sizeof(uint32_t)));
second_addr = *(uint32_t *)(p_second_addr + (i * sizeof(uint32_t)));
if (first_addr < second_addr)
{
return -1;
}
else if (first_addr > second_addr)
{
return 1;
}
}
return 0;
}
/**
* @brief Compare two short addresses.
*
* @param[in] p_first_addr Pointer to a first address that should be compared.
* @param[in] p_second_addr Pointer to a second address that should be compared.
*
* @retval -1 First address is less than the second address.
* @retval 0 First address is equal to the second address.
* @retval 1 First address is greater than the second address.
*/
static int8_t short_addr_compare(const uint8_t * p_first_addr, const uint8_t * p_second_addr)
{
uint16_t first_addr = *(uint16_t *)(p_first_addr);
uint16_t second_addr = *(uint16_t *)(p_second_addr);
if (first_addr < second_addr)
{
return -1;
}
else if (first_addr > second_addr)
{
return 1;
}
else
{
return 0;
}
}
/**
* @brief Compare two addresses.
*
* @param[in] p_first_addr Pointer to a first address that should be compared.
* @param[in] p_second_addr Pointer to a second address that should be compared.
* @param[in] extended Indication if @p p_first_addr and @p p_second_addr are extended or short addresses.
*
* @retval -1 First address is less than the second address.
* @retval 0 First address is equal to the second address.
* @retval 1 First address is greater than the second address.
*/
static int8_t addr_compare(const uint8_t * p_first_addr,
const uint8_t * p_second_addr,
bool extended)
{
if (extended)
{
return extended_addr_compare(p_first_addr, p_second_addr);
}
else
{
return short_addr_compare(p_first_addr, p_second_addr);
}
}
/**
* @brief Perform a binary search for an address in a list of addresses.
*
* @param[in] p_addr Pointer to an address that is searched for.
* @param[in] p_addr_array Pointer to a list of addresses to be searched.
* @param[out] p_location If the address @p p_addr appears in the list, this is its index in the address list.
* Otherwise, it is the index which @p p_addr would have if it was placed in the list
* (ascending order assumed).
* @param[in] extended Indication if @p p_addr is an extended or a short addresses.
*
* @retval true Address @p p_addr is in the list.
* @retval false Address @p p_addr is not in the list.
*/
static bool addr_binary_search(const uint8_t * p_addr,
const uint8_t * p_addr_array,
uint8_t * p_location,
bool extended)
{
uint8_t addr_array_len = extended ? m_num_of_pending_extended : m_num_of_pending_short;
uint8_t entry_size = extended ? EXTENDED_ADDRESS_SIZE : SHORT_ADDRESS_SIZE;
int8_t low = 0;
int8_t midpoint = 0;
int8_t high = addr_array_len;
while (high >= low)
{
midpoint = low + (high - low) / 2;
if (midpoint >= addr_array_len)
{
break;
}
switch (addr_compare(p_addr, p_addr_array + entry_size * midpoint, extended))
{
case -1:
high = midpoint - 1;
break;
case 0:
*p_location = midpoint;
return true;
case 1:
low = midpoint + 1;
break;
default:
break;
}
}
/* If in the last iteration of the loop the last case was utilized, it means that the midpoint
* found by the algorithm is less than the address to be added. The midpoint should be therefore
* shifted to the next position. As a simplified example, a { 1, 3, 4 } array can be considered.
* Suppose that a number equal to 2 is about to be added to the array. At the beginning of the
* last iteration, midpoint is equal to 1 and low and high are equal to 0. Midpoint is then set
* to 0 and with last case being utilized, low is set to 1. However, midpoint equal to 0 is
* incorrect, as in the last iteration first element of the array proves to be less than the
* element to be added to the array. With the below code, midpoint is then shifted to 1. */
if (low == midpoint + 1)
{
midpoint++;
}
*p_location = midpoint;
return false;
}
/**
* @brief Find an address in a list of addresses.
*
* @param[in] p_addr Pointer to an address that is searched for.
* @param[out] p_location If the address @p p_addr appears in the list, this is its index in the address list.
* Otherwise, it is the index which @p p_addr would have if it was placed in the list
* (ascending order assumed).
* @param[in] extended Indication if @p p_addr is an extended or a short addresses.
*
* @retval true Address @p p_addr is in the list.
* @retval false Address @p p_addr is not in the list.
*/
static bool addr_index_find(const uint8_t * p_addr,
uint8_t * p_location,
bool extended)
{
if (extended)
{
return addr_binary_search(p_addr, (uint8_t *)m_pending_extended, p_location, extended);
}
else
{
return addr_binary_search(p_addr, (uint8_t *)m_pending_short, p_location, extended);
}
}
/**
* @brief Add an address to the address list in ascending order.
*
* @param[in] p_addr Pointer to the address to be added.
* @param[in] location Index of the location where @p p_addr should be added.
* @param[in] extended Indication if @p p_addr is an extended or a short addresses.
*
* @retval true Address @p p_addr has been added to the list successfully.
* @retval false Address @p p_addr could not be added to the list.
*/
static bool addr_add(const uint8_t * p_addr, uint8_t location, bool extended)
{
uint8_t * p_addr_array;
uint8_t max_addr_array_len;
uint8_t * p_addr_array_len;
uint8_t entry_size;
p_addr_array = extended ? (uint8_t *)m_pending_extended : (uint8_t *)m_pending_short;
max_addr_array_len = extended ? NUM_PENDING_EXTENDED_ADDRESSES : NUM_PENDING_SHORT_ADDRESSES;
p_addr_array_len = extended ? &m_num_of_pending_extended : &m_num_of_pending_short;
entry_size = extended ? EXTENDED_ADDRESS_SIZE : SHORT_ADDRESS_SIZE;
if (*p_addr_array_len == max_addr_array_len)
{
return false;
}
memmove(p_addr_array + entry_size * (location + 1),
p_addr_array + entry_size * (location),
(*p_addr_array_len - location) * entry_size);
memcpy(p_addr_array + entry_size * location, p_addr, entry_size);
(*p_addr_array_len)++;
return true;
}
/**
* @brief Remove an address from the address list keeping it in ascending order.
*
* @param[in] location Index of the element to be removed from the list.
* @param[in] extended Indication if address to remove is an extended or a short address.
*
* @retval true Address @p p_addr has been removed from the list successfully.
* @retval false Address @p p_addr could not removed from the list.
*/
static bool addr_remove(uint8_t location, bool extended)
{
uint8_t * p_addr_array;
uint8_t * p_addr_array_len;
uint8_t entry_size;
p_addr_array = extended ? (uint8_t *)m_pending_extended : (uint8_t *)m_pending_short;
p_addr_array_len = extended ? &m_num_of_pending_extended : &m_num_of_pending_short;
entry_size = extended ? EXTENDED_ADDRESS_SIZE : SHORT_ADDRESS_SIZE;
if (*p_addr_array_len == 0)
{
return false;
}
memmove(p_addr_array + entry_size * location,
p_addr_array + entry_size * (location + 1),
(*p_addr_array_len - location - 1) * entry_size);
(*p_addr_array_len)--;
return true;
}
void nrf_802154_ack_pending_bit_init(void)
{
m_setting_pending_bit_enabled = true;
m_num_of_pending_extended = 0;
m_num_of_pending_short = 0;
}
void nrf_802154_ack_pending_bit_set(bool enabled)
{
m_setting_pending_bit_enabled = enabled;
}
bool nrf_802154_ack_pending_bit_for_addr_set(const uint8_t * p_addr, bool extended)
{
uint8_t location = 0;
if (addr_index_find(p_addr, &location, extended))
{
return true;
}
else
{
return addr_add(p_addr, location, extended);
}
}
bool nrf_802154_ack_pending_bit_for_addr_clear(const uint8_t * p_addr, bool extended)
{
uint8_t location = 0;
if (addr_index_find(p_addr, &location, extended))
{
return addr_remove(location, extended);
}
else
{
return false;
}
}
void nrf_802154_ack_pending_bit_for_addr_reset(bool extended)
{
if (extended)
{
m_num_of_pending_extended = 0;
}
else
{
m_num_of_pending_short = 0;
}
}
bool nrf_802154_ack_pending_bit_should_be_set(const uint8_t * p_psdu)
{
const uint8_t * p_src_addr;
uint8_t location;
bool extended;
// If automatic setting of pending bit in ACK frames is disabled the pending bit is always set.
if (!m_setting_pending_bit_enabled)
{
return true;
}
switch (p_psdu[DEST_ADDR_TYPE_OFFSET] & DEST_ADDR_TYPE_MASK)
{
case DEST_ADDR_TYPE_SHORT:
p_src_addr = &p_psdu[SRC_ADDR_OFFSET_SHORT_DST];
break;
case DEST_ADDR_TYPE_EXTENDED:
p_src_addr = &p_psdu[SRC_ADDR_OFFSET_EXTENDED_DST];
break;
default:
return true;
}
if (0 == (p_psdu[PAN_ID_COMPR_OFFSET] & PAN_ID_COMPR_MASK))
{
p_src_addr += PAN_ID_SIZE;
}
switch (p_psdu[SRC_ADDR_TYPE_OFFSET] & SRC_ADDR_TYPE_MASK)
{
case SRC_ADDR_TYPE_SHORT:
extended = false;
break;
case SRC_ADDR_TYPE_EXTENDED:
extended = true;
break;
default:
return true;
}
return addr_index_find(p_src_addr, &location, extended);
}

View file

@ -1,110 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This file implements procedures to set pending bit in nRF 802.15.4 radio driver.
*
*/
#ifndef NRF_802154_ACK_PENDING_BIT_H_
#define NRF_802154_ACK_PENDING_BIT_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Initialize this module.
*/
void nrf_802154_ack_pending_bit_init(void);
/**
* @brief Enable or disable procedure of setting pending bit in ACK frame.
*
* @param[in] enabled True if procedure should be enabled, false otherwise.
*/
void nrf_802154_ack_pending_bit_set(bool enabled);
/**
* @brief Add address to ACK pending bit list.
*
* ACK frames sent in response to frames with source address matching any address from ACK pending
* bit list will have pending bit set. If source address does not match any of the addresses in the
* list the ACK frame will have pending bit cleared.
*
* @param[in] p_addr Pointer to address that should be added to the list.
* @param[in] extended Indication if @p p_addr is extended or short address.
*
* @retval true Address successfully added to the list.
* @retval false Address was not added to the list (list is full).
*/
bool nrf_802154_ack_pending_bit_for_addr_set(const uint8_t * p_addr, bool extended);
/**
* @brief Remove address from ACK pending bit list.
*
* ACK frames sent in response to frames with source address matching any address from ACK pending
* bit list will have pending bit set. If source address does not match any of the addresses in the
* list the ACK frame will have pending bit cleared.
*
* @param[in] p_addr Pointer to address that should be removed from the list.
* @param[in] extended Indication if @p p_addr is extended or short address.
*
* @retval true Address successfully removed from the list.
* @retval false Address was not removed from the list (address is missing in the list).
*/
bool nrf_802154_ack_pending_bit_for_addr_clear(const uint8_t * p_addr, bool extended);
/**
* @brief Remove all addresses of given length from ACK pending bit list.
*
* @param[in] extended Indication if all extended or all short addresses should be removed from
* the list.
*/
void nrf_802154_ack_pending_bit_for_addr_reset(bool extended);
/**
* @brief Check if pending bit should be set in ACK sent in response to given frame.
*
* @param[in] p_psdu PSDU of frame to which ACK frame is being prepared.
*
* @retval true Pending bit should be set.
* @retval false Pending bit should be cleared.
*/
bool nrf_802154_ack_pending_bit_should_be_set(const uint8_t * p_psdu);
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_ACK_PENDING_BIT_H_ */

View file

@ -1,495 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_CONFIG_H__
#define NRF_802154_CONFIG_H__
#ifdef NRF_802154_PROJECT_CONFIG
#include NRF_802154_PROJECT_CONFIG
#endif
#include <nrf.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_config 802.15.4 driver configuration
* @{
* @ingroup nrf_802154
* @brief Configuration of the 802.15.4 radio driver for nRF SoCs.
*/
/**
* @defgroup nrf_802154_config_radio Radio driver configuration
* @{
*/
/**
* @def NRF_802154_CCA_MODE_DEFAULT
*
* CCA mode used by the driver.
*
*/
#ifndef NRF_802154_CCA_MODE_DEFAULT
#define NRF_802154_CCA_MODE_DEFAULT NRF_RADIO_CCA_MODE_ED
#endif
/**
* @def NRF_802154_CCA_ED_THRESHOLD_DEFAULT
*
* Energy detection threshold used in CCA procedure.
*
*/
#ifndef NRF_802154_CCA_ED_THRESHOLD_DEFAULT
#define NRF_802154_CCA_ED_THRESHOLD_DEFAULT 0x14
#endif
/**
* @def NRF_802154_CCA_CORR_THRESHOLD_DEFAULT
*
* Correlator threshold used in CCA procedure.
*
*/
#ifndef NRF_802154_CCA_CORR_THRESHOLD_DEFAULT
#define NRF_802154_CCA_CORR_THRESHOLD_DEFAULT 0x14
#endif
/**
* @def NRF_802154_CCA_CORR_LIMIT_DEFAULT
*
* Correlator limit used in CCA procedure.
*
*/
#ifndef NRF_802154_CCA_CORR_LIMIT_DEFAULT
#define NRF_802154_CCA_CORR_LIMIT_DEFAULT 0x02
#endif
/**
* @def NRF_802154_INTERNAL_RADIO_IRQ_HANDLING
*
* If the driver should internally handle the RADIO IRQ.
* If the driver is used in an OS, the RADIO IRQ may be handled by the OS and passed to
* the driver by @ref nrf_802154_radio_irq_handler. In this case, internal handling should be disabled.
*/
#ifndef NRF_802154_INTERNAL_RADIO_IRQ_HANDLING
#if RAAL_SOFTDEVICE || RAAL_REM
#define NRF_802154_INTERNAL_RADIO_IRQ_HANDLING 0
#else // RAAL_SOFTDEVICE || RAAL_REM
#define NRF_802154_INTERNAL_RADIO_IRQ_HANDLING 1
#endif // RAAL_SOFTDEVICE || RAAL_REM
#endif // NRF_802154_INTERNAL_RADIO_IRQ_HANDLING
/**
* @def NRF_802154_IRQ_PRIORITY
*
* Interrupt priority for RADIO peripheral.
* Keep IRQ priority high (low number) to prevent losing frames due to
* preemption.
*
*/
#ifndef NRF_802154_IRQ_PRIORITY
#define NRF_802154_IRQ_PRIORITY 0
#endif
/**
* @def NRF_802154_TIMER_INSTANCE
*
* Timer instance used by the driver for ACK IFS and by the FEM module.
*
*/
#ifndef NRF_802154_TIMER_INSTANCE
#define NRF_802154_TIMER_INSTANCE NRF_TIMER1
#endif
/**
* @def NRF_802154_COUNTER_TIMER_INSTANCE
*
* Timer instance used by the driver for detecting when PSDU is being received.
*
* @note This configuration is used only when NRF_RADIO_EVENT_BCMATCH event handling is disabled
* (see @ref NRF_802154_DISABLE_BCC_MATCHING).
*/
#ifndef NRF_802154_COUNTER_TIMER_INSTANCE
#define NRF_802154_COUNTER_TIMER_INSTANCE NRF_TIMER0
#endif
/**
* @def NRF_802154_SWI_EGU_INSTANCE
*
* SWI EGU instance used by the driver to synchronize PPIs and for requests and notifications if
* SWI is in use.
*
* @note This option is used by the core module regardless of the driver configuration.
*
*/
#ifndef NRF_802154_SWI_EGU_INSTANCE
#define NRF_802154_SWI_EGU_INSTANCE NRF_EGU3
#endif
/**
* @def NRF_802154_SWI_IRQ_HANDLER
*
* SWI EGU IRQ handler used by the driver for requests and notifications if SWI is in use.
*
* @note This option is used when the driver uses SWI to process requests and notifications.
*
*/
#ifndef NRF_802154_SWI_IRQ_HANDLER
#define NRF_802154_SWI_IRQ_HANDLER SWI3_EGU3_IRQHandler
#endif
/**
* @def NRF_802154_SWI_IRQN
*
* SWI EGU IRQ number used by the driver for requests and notifications if SWI is in use.
*
* @note This option is used when the driver uses SWI to process requests and notifications.
*
*/
#ifndef NRF_802154_SWI_IRQN
#define NRF_802154_SWI_IRQN SWI3_EGU3_IRQn
#endif
/**
* @def NRF_802154_SWI_PRIORITY
*
* Priority of software interrupt used for requests and notifications.
*
*/
#ifndef NRF_802154_SWI_PRIORITY
#define NRF_802154_SWI_PRIORITY 5
#endif
/**
* @def NRF_802154_USE_RAW_API
*
* When this flag is set, RAW API is available for the MAC layer. It is recommended to use RAW API
* because it provides more optimized functions.
*
* @note If RAW API is not available for the MAC layer, only less optimized functions performing
* copy are available.
*
*/
#ifndef NRF_802154_USE_RAW_API
#define NRF_802154_USE_RAW_API 1
#endif
/**
* @def NRF_802154_PENDING_SHORT_ADDRESSES
*
* Number of slots containing short addresses of nodes for which pending data is stored.
*
*/
#ifndef NRF_802154_PENDING_SHORT_ADDRESSES
#define NRF_802154_PENDING_SHORT_ADDRESSES 10
#endif
/**
* @def NRF_802154_PENDING_EXTENDED_ADDRESSES
*
* Number of slots containing extended addresses of nodes for which pending data is stored.
*
*/
#ifndef NRF_802154_PENDING_EXTENDED_ADDRESSES
#define NRF_802154_PENDING_EXTENDED_ADDRESSES 10
#endif
/**
* @def NRF_802154_RX_BUFFERS
*
* Number of buffers in receive queue.
*
*/
#ifndef NRF_802154_RX_BUFFERS
#define NRF_802154_RX_BUFFERS 16
#endif
/**
* @def NRF_802154_DISABLE_BCC_MATCHING
*
* Setting this flag disables NRF_RADIO_EVENT_BCMATCH handling, and therefore address filtering
* during frame reception. With this flag set to 1, address filtering is done after receiving
* a frame, during NRF_RADIO_EVENT_END handling.
*
*/
#ifndef NRF_802154_DISABLE_BCC_MATCHING
#define NRF_802154_DISABLE_BCC_MATCHING 0
#endif
/**
* @def NRF_802154_NOTIFY_CRCERROR
*
* With this flag set to 1, CRC errors are notified to upper layers. This requires an interrupt
* handler to be used.
*
*/
#ifndef NRF_802154_NOTIFY_CRCERROR
#define NRF_802154_NOTIFY_CRCERROR 1
#endif
/**
* @def NRF_802154_FRAME_TIMESTAMP_ENABLED
*
* If timestamps should be added to received frames.
* Enabling this feature enables the functions @ref nrf_802154_received_timsestamp_raw,
* @ref nrf_802154_received_timestamp, @ref nrf_802154_transmitted_timestamp_raw, and
* @ref nrf_802154_transmitted_timestamp, which add timestamps to received frames.
*
*/
#ifndef NRF_802154_FRAME_TIMESTAMP_ENABLED
#define NRF_802154_FRAME_TIMESTAMP_ENABLED 1
#endif
/**
* @def NRF_802154_DELAYED_TRX_ENABLED
*
* If delayed transmission and receive window features are available.
*
*/
#ifndef NRF_802154_DELAYED_TRX_ENABLED
#define NRF_802154_DELAYED_TRX_ENABLED 1
#endif
/**
* @}
* @defgroup nrf_802154_config_clock Clock driver configuration
* @{
*/
/**
* @def NRF_802154_CLOCK_IRQ_PRIORITY
*
* Priority of clock interrupt used in standalone clock driver implementation.
*
* @note This configuration is only applicable for the Clock Abstraction Layer implementation
* in nrf_802154_clock_nodrv.c.
*
*/
#ifndef NRF_802154_CLOCK_IRQ_PRIORITY
#define NRF_802154_CLOCK_IRQ_PRIORITY 10
#endif
/**
* @def NRF_802154_CLOCK_LFCLK_SOURCE
*
* Low-frequency clock source used in standalone clock driver implementation.
*
* @note This configuration is only applicable for the Clock Abstraction Layer implementation
* in nrf_802154_clock_nodrv.c.
*
*/
#ifndef NRF_802154_CLOCK_LFCLK_SOURCE
#define NRF_802154_CLOCK_LFCLK_SOURCE NRF_CLOCK_LFCLK_Xtal
#endif
/**
* @}
* @defgroup nrf_802154_config_rtc RTC driver configuration
* @{
*/
/**
* @def NRF_802154_RTC_IRQ_PRIORITY
*
* Priority of RTC interrupt used in standalone timer driver implementation.
*
* @note This configuration is only applicable for the Low Power Timer Abstraction Layer implementation
* in nrf_802154_lp_timer_nodrv.c.
*
*/
#ifndef NRF_802154_RTC_IRQ_PRIORITY
#define NRF_802154_RTC_IRQ_PRIORITY 6
#endif
/**
* @def NRF_802154_RTC_INSTANCE
*
* RTC instance used in standalone timer driver implementation.
*
* @note This configuration is only applicable for the Low Power Timer Abstraction Layer implementation
* in nrf_802154_lp_timer_nodrv.c.
*
*/
#ifndef NRF_802154_RTC_INSTANCE
#define NRF_802154_RTC_INSTANCE NRF_RTC2
#endif
/**
* @def NRF_802154_RTC_IRQ_HANDLER
*
* RTC interrupt handler name used in standalone timer driver implementation.
*
* @note This configuration is only applicable for Low Power Timer Abstraction Layer implementation
* in nrf_802154_lp_timer_nodrv.c.
*
*/
#ifndef NRF_802154_RTC_IRQ_HANDLER
#define NRF_802154_RTC_IRQ_HANDLER RTC2_IRQHandler
#endif
/**
* @def NRF_802154_RTC_IRQN
*
* RTC Interrupt number used in standalone timer driver implementation.
*
* @note This configuration is only applicable for the Low Power Timer Abstraction Layer implementation
* in nrf_802154_lp_timer_nodrv.c.
*
*/
#ifndef NRF_802154_RTC_IRQN
#define NRF_802154_RTC_IRQN RTC2_IRQn
#endif
/**
* @}
* @defgroup nrf_802154_config_csma CSMA/CA procedure configuration
* @{
*/
/**
* @def NRF_802154_CSMA_CA_ENABLED
*
* If CSMA-CA should be enabled by the driver. Disabling CSMA-CA improves
* driver performance.
*
*/
#ifndef NRF_802154_CSMA_CA_ENABLED
#define NRF_802154_CSMA_CA_ENABLED 1
#endif
/**
* @def NRF_802154_CSMA_CA_MIN_BE
*
* The minimum value of the backoff exponent (BE) in the CSMA-CA algorithm
* (IEEE 802.15.4-2015: 6.2.5.1).
*
*/
#ifndef NRF_802154_CSMA_CA_MIN_BE
#define NRF_802154_CSMA_CA_MIN_BE 3
#endif
/**
* @def NRF_802154_CSMA_CA_MAX_BE
*
* The maximum value of the backoff exponent, BE, in the CSMA-CA algorithm
* (IEEE 802.15.4-2015: 6.2.5.1).
*
*/
#ifndef NRF_802154_CSMA_CA_MAX_BE
#define NRF_802154_CSMA_CA_MAX_BE 5
#endif
/**
* @def NRF_802154_CSMA_CA_MAX_CSMA_BACKOFFS
*
* The maximum number of backoffs that the CSMA-CA algorithm will attempt before declaring a channel
* access failure.
*
*/
#ifndef NRF_802154_CSMA_CA_MAX_CSMA_BACKOFFS
#define NRF_802154_CSMA_CA_MAX_CSMA_BACKOFFS 4
#endif
/**
* @}
* @defgroup nrf_802154_config_timeout ACK timeout feature configuration
* @{
*/
/**
* @def NRF_802154_ACK_TIMEOUT_ENABLED
*
* If the ACK timeout feature should be enabled in the driver.
*
*/
#ifndef NRF_802154_ACK_TIMEOUT_ENABLED
#define NRF_802154_ACK_TIMEOUT_ENABLED 1
#endif
/**
* @def NRF_802154_ACK_TIMEOUT_DEFAULT_TIMEOUT
*
* Default timeout in us for the ACK timeout feature.
*
*/
#ifndef NRF_802154_ACK_TIMEOUT_DEFAULT_TIMEOUT
#define NRF_802154_ACK_TIMEOUT_DEFAULT_TIMEOUT 7000
#endif
/**
* @def NRF_802154_ACK_TIMEOUT_DEFAULT_TIMEOUT
*
* Default time-out in us for the precise ACK time-out feature.
*
*/
#ifndef NRF_802154_PRECISE_ACK_TIMEOUT_DEFAULT_TIMEOUT
#define NRF_802154_PRECISE_ACK_TIMEOUT_DEFAULT_TIMEOUT 210
#endif
/**
* @}
* @defgroup nrf_802154_config_transmission Transmission start notification feature configuration
* @{
*/
/**
* @def NRF_802154_TX_STARTED_NOTIFY_ENABLED
*
* If notifications of started transmissions should be enabled in the driver.
*
* @note This feature is enabled by default if the ACK timeout feature or CSMA-CA is enabled.
* These features depend on notifications of transmission start.
*/
#ifndef NRF_802154_TX_STARTED_NOTIFY_ENABLED
#if NRF_802154_ACK_TIMEOUT_ENABLED || NRF_802154_CSMA_CA_ENABLED
#define NRF_802154_TX_STARTED_NOTIFY_ENABLED 1
#else
#define NRF_802154_TX_STARTED_NOTIFY_ENABLED 0
#endif
#endif // NRF_802154_TX_STARTED_NOTIFY_ENABLED
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_802154_CONFIG_H__
/**
*@}
**/

View file

@ -1,130 +0,0 @@
/* Copyright (c) 2017, Nordic Semiconductor ASA
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module contains constant values definitions used by nRF 802.15.4 driver.
*
*/
#ifndef NRF_802154_CONST_H_
#define NRF_802154_CONST_H_
#include <stdint.h>
#include "nrf_802154_config.h"
#define ACK_HEADER_WITH_PENDING 0x12 ///< First byte of ACK frame containing pending bit.
#define ACK_HEADER_WITHOUT_PENDING 0x02 ///< First byte of ACK frame without pending bit.
#define ACK_REQUEST_OFFSET 1 ///< Byte containing Ack request bit (+1 for frame length byte).
#define ACK_REQUEST_BIT (1 << 5) ///< Ack request bit.
#define DEST_ADDR_TYPE_OFFSET 2 ///< Byte containing destination address type (+1 for frame length byte).
#define DEST_ADDR_TYPE_MASK 0x0c ///< Mask of bits containing destination address type.
#define DEST_ADDR_TYPE_EXTENDED 0x0c ///< Bits containing extended destination address type.
#define DEST_ADDR_TYPE_NONE 0x00 ///< Bits containing not present destination address type.
#define DEST_ADDR_TYPE_SHORT 0x08 ///< Bits containing short destination address type.
#define DEST_ADDR_OFFSET 6 ///< Offset of destination address in Data frame (+1 for frame length byte).
#define DSN_OFFSET 3 ///< Byte containing DSN value (+1 for frame length byte).
#define FRAME_PENDING_OFFSET 1 ///< Byte containing pending bit (+1 for frame length byte).
#define FRAME_PENDING_BIT (1 << 4) ///< Pending bit.
#define FRAME_TYPE_OFFSET 1 ///< Byte containing frame type bits (+1 for frame length byte).
#define FRAME_TYPE_MASK 0x07 ///< Mask of bits containing frame type.
#define FRAME_TYPE_ACK 0x02 ///< Bits containing ACK frame type.
#define FRAME_TYPE_BEACON 0x00 ///< Bits containing Beacon frame type.
#define FRAME_TYPE_COMMAND 0x03 ///< Bits containing Command frame type.
#define FRAME_TYPE_DATA 0x01 ///< Bits containing Data frame type.
#define FRAME_TYPE_EXTENDED 0x07 ///< Bits containing Extended frame type.
#define FRAME_TYPE_FRAGMENT 0x06 ///< Bits containing Fragment or Frak frame type.
#define FRAME_TYPE_MULTIPURPOSE 0x05 ///< Bits containing Multipurpose frame type.
#define FRAME_VERSION_OFFSET 2 ///< Byte containing frame version bits (+1 for frame length byte).
#define FRAME_VERSION_MASK 0x30 ///< Mask of bits containing frame version.
#define FRAME_VERSION_0 0x00 ///< Bits containing frame version 0b00.
#define FRAME_VERSION_1 0x10 ///< Bits containing frame version 0b01.
#define FRAME_VERSION_2 0x20 ///< Bits containing frame version 0b10.
#define FRAME_VERSION_3 0x30 ///< Bits containing frame version 0b11.
#define PAN_ID_COMPR_OFFSET 1 ///< Byte containing Pan Id compression bit (+1 for frame length byte).
#define PAN_ID_COMPR_MASK 0x40 ///< Pan Id compression bit.
#define PAN_ID_OFFSET 4 ///< Offset of Pan Id in Data frame (+1 for frame length byte).
#define SRC_ADDR_TYPE_EXTENDED 0xc0 ///< Bits containing extended source address type.
#define SRC_ADDR_TYPE_NONE 0x00 ///< Bits containing not present source address type.
#define SRC_ADDR_TYPE_MASK 0xc0 ///< Mask of bits containing source address type.
#define SRC_ADDR_TYPE_OFFSET 2 ///< Byte containing source address type (+1 for frame length byte).
#define SRC_ADDR_TYPE_SHORT 0x80 ///< Bits containing short source address type.
#define SRC_ADDR_OFFSET_SHORT_DST 8 ///< Offset of source address in Data frame if destination address is short.
#define SRC_ADDR_OFFSET_EXTENDED_DST 14 ///< Offset of source address in Data frame if destination address is extended.
#define PHR_SIZE 1 ///< Size of PHR field.
#define FCF_SIZE 2 ///< Size of FCF field.
#define PAN_ID_SIZE 2 ///< Size of Pan Id.
#define SHORT_ADDRESS_SIZE 2 ///< Size of Short Mac Address.
#define EXTENDED_ADDRESS_SIZE 8 ///< Size of Extended Mac Address.
#define FCS_SIZE 2 ///< Size of FCS field.
#define IMM_ACK_LENGTH 5 ///< Length of ACK frame.
#define MAX_PACKET_SIZE 127 ///< Maximum size of radio packet.
#define TURNAROUND_TIME 192UL ///< aTurnaroundTime [us].
#define CCA_TIME 128UL ///< aCcaTime [us].
#define UNIT_BACKOFF_PERIOD (TURNAROUND_TIME + CCA_TIME) ///< aUnitBackoffPeriod [us].
#define PHY_US_PER_SYMBOL 16 ///< Duration of a single symbol in microseconds [us].
#define PHY_SYMBOLS_PER_OCTET 2 ///< Number of symbols in a single byte (octet).
#define PHY_SHR_SYMBOLS 10 ///< Number of symbols in Synchronization Header (SHR).
#define ED_MIN_DBM (-94) ///< dBm value corresponding to value 0 in EDSAMPLE register.
#define ED_RESULT_FACTOR 4 ///< Factor needed to calculate ED result based on data from RADIO peripheral.
#define ED_RESULT_MAX 0xff ///< Maximal ED result.
#define BROADCAST_ADDRESS ((uint8_t[SHORT_ADDRESS_SIZE]) {0xff, 0xff}) ///< Broadcast Short Address.
typedef enum
{
REQ_ORIG_HIGHER_LAYER,
REQ_ORIG_CORE,
REQ_ORIG_RSCH,
#if NRF_802154_CSMA_CA_ENABLED
REQ_ORIG_CSMA_CA,
#endif // NRF_802154_CSMA_CA_ENABLED
#if NRF_802154_ACK_TIMEOUT_ENABLED
REQ_ORIG_ACK_TIMEOUT,
#endif // NRF_802154_ACK_TIMEOUT_ENABLED
#if NRF_802154_DELAYED_TRX_ENABLED
REQ_ORIG_DELAYED_TRX,
#endif // NRF_802154_DELAYED_TRX_ENABLED
} req_originator_t;
#endif // NRD_DRV_RADIO802154_CONST_H_

File diff suppressed because it is too large Load diff

View file

@ -1,241 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module contains core of the nRF IEEE 802.15.4 radio driver.
*
*/
#ifndef NRF_802154_CORE_H_
#define NRF_802154_CORE_H_
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_config.h"
#include "nrf_802154_notification.h"
#include "nrf_802154_rx_buffer.h"
#include "nrf_802154_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief States of nRF 802.15.4 driver.
*/
typedef enum
{
// Sleep
RADIO_STATE_SLEEP, ///< Low power (DISABLED) mode - the only state in which all radio preconditions ane not requested.
RADIO_STATE_FALLING_ASLEEP, ///< Prior entering SLEEP state all radio preconditions are requested.
// Receive
RADIO_STATE_RX, ///< Receiver is enabled and it is receiving frames.
RADIO_STATE_TX_ACK, ///< Received frame and transmitting ACK.
// Transmit
RADIO_STATE_CCA_TX, ///< Performing CCA followed by frame transmission.
RADIO_STATE_TX, ///< Transmitting data frame (or beacon).
RADIO_STATE_RX_ACK, ///< Receiving ACK after transmitted frame.
// Energy Detection
RADIO_STATE_ED, ///< Performing Energy Detection procedure.
// CCA
RADIO_STATE_CCA, ///< Performing CCA procedure.
// Continuous carrier
RADIO_STATE_CONTINUOUS_CARRIER, ///< Emitting continuous carrier wave.
} radio_state_t;
/**
* @brief Initialize 802.15.4 driver core.
*/
void nrf_802154_core_init(void);
/**
* @brief Deinitialize 802.15.4 driver core.
*/
void nrf_802154_core_deinit(void);
/**
* @brief Get current state of nRF 802.15.4 driver.
*
* @return Current state of the 802.15.4 driver.
*/
radio_state_t nrf_802154_core_state_get(void);
/***************************************************************************************************
* @section State machine transition requests
**************************************************************************************************/
/**
* @brief Request transition to SLEEP state.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Shceduler notification.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
*
* @retval true Entering SLEEP state succeeded.
* @retval false Entering SLEEP state failed (driver is performing other procedure).
*/
bool nrf_802154_core_sleep(nrf_802154_term_t term_lvl);
/**
* @brief Request transition to RECEIVE state.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Scheduler notification.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @param[in] notify_function Function called to notify status of this procedure. May be NULL.
* @param[in] notify_abort If abort notification should be triggered.
*
* @retval true Entering RECEIVE state succeeded.
* @retval false Entering RECEIVE state failed (driver is performing other procedure).
*/
bool nrf_802154_core_receive(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
nrf_802154_notification_func_t notify_function,
bool notify_abort);
/**
* @brief Request transition to TRANSMIT state.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Scheduler notification.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @param[in] p_data Pointer to a frame to transmit.
* @param[in] cca If the driver should perform CCA procedure before transmission.
* @param[in] immediate If true, the driver schedules transmission immediately or never;
* if false transmission may be postponed until tx preconditions are
* met.
* @param[in] notify_function Function called to notify status of this procedure. May be NULL.
*
* @retval true Entering TRANSMIT state succeeded.
* @retval false Entering TRANSMIT state failed (driver is performing other procedure).
*/
bool nrf_802154_core_transmit(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
const uint8_t * p_data,
bool cca,
bool immediate,
nrf_802154_notification_func_t notify_function);
/**
* @brief Request transition to ENERGY_DETECTION state.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Scheduler notification.
*
* @note This function shall be called when the driver is in SLEEP or RECEIVE state. When Energy
* detection procedure is finished the driver will transit to RECEIVE state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] time_us Minimal time of energy detection procedure.
*
* @retval true Entering ENERGY_DETECTION state succeeded.
* @retval false Entering ENERGY_DETECTION state failed (driver is performing other procedure).
*/
bool nrf_802154_core_energy_detection(nrf_802154_term_t term_lvl, uint32_t time_us);
/**
* @brief Request transition to CCA state.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Scheduler notification.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
*
* @retval true Entering CCA state succeeded.
* @retval false Entering CCA state failed (driver is performing other procedure).
*/
bool nrf_802154_core_cca(nrf_802154_term_t term_lvl);
/**
* @brief Request transition to CONTINUOUS_CARRIER state.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Scheduler notification.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
*
* @retval true Entering CONTINUOUS_CARRIER state succeeded.
* @retval false Entering CONTINUOUS_CARRIER state failed (driver is performing other procedure).
*/
bool nrf_802154_core_continuous_carrier(nrf_802154_term_t term_lvl);
/***************************************************************************************************
* @section State machine notifications
**************************************************************************************************/
/**
* @brief Notify the Core module that higher layer freed a frame buffer.
*
* When there were no free buffers available the core does not start receiver. If core receives this
* notification it changes internal state to make sure receiver is started if requested.
*
* @note This function shall be called from a critical section context. It shall not be interrupted
* by the RADIO event handler or Radio Scheduler notification.
*
* @param[in] p_data Pointer to buffer that has been freed.
*/
bool nrf_802154_core_notify_buffer_free(uint8_t * p_data);
/**
* @brief Notify the Core module that next higher layer requested change of the channel.
*
* Core should update frequency register of the peripheral and in case it is in RECEIVE state the
* receiver should be disabled and enabled again to use new channel.
*/
bool nrf_802154_core_channel_update(void);
/**
* @brief Notify the Core module that next higher layer requested change of the CCA configuration.
*/
bool nrf_802154_core_cca_cfg_update(void);
#if !NRF_802154_INTERNAL_IRQ_HANDLING
/**
* @brief Notify the Core module that there is a pending IRQ that should be handled.
*/
void nrf_802154_core_irq_handler(void);
#endif // !NRF_802154_INTERNAL_IRQ_HANDLING
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_CORE_H_ */

View file

@ -1,212 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements hooks for the 802.15.4 driver Core module.
*
* Hooks are used by optional driver features to modify way in which notifications are propagated
* through the driver.
*
*/
#include "nrf_802154_core_hooks.h"
#include <stdbool.h>
#include "mac_features/nrf_802154_ack_timeout.h"
#include "mac_features/nrf_802154_csma_ca.h"
#include "mac_features/nrf_802154_delayed_trx.h"
#include "nrf_802154_config.h"
#include "nrf_802154_types.h"
typedef bool (* abort_hook)(nrf_802154_term_t term_lvl, req_originator_t req_orig);
typedef void (* transmitted_hook)(const uint8_t * p_frame);
typedef bool (* tx_failed_hook)(const uint8_t * p_frame, nrf_802154_tx_error_t error);
typedef bool (* tx_started_hook)(const uint8_t * p_frame);
typedef void (* rx_started_hook)(void);
/* Since some compilers do not allow empty initializers for arrays with unspecified bounds,
* NULL pointer is appended to below arrays if the compiler used is not GCC. It is intentionally
* unused, but it prevents the arrays from being empty. GCC manages to optimize empty arrays away,
* so such a solution is unnecessary. */
static const abort_hook m_abort_hooks[] =
{
#if NRF_802154_CSMA_CA_ENABLED
nrf_802154_csma_ca_abort,
#endif
#if NRF_802154_ACK_TIMEOUT_ENABLED
nrf_802154_ack_timeout_abort,
#endif
#if NRF_802154_DELAYED_TRX_ENABLED
nrf_802154_delayed_trx_abort,
#endif
NULL,
};
static const transmitted_hook m_transmitted_hooks[] =
{
#if NRF_802154_ACK_TIMEOUT_ENABLED
nrf_802154_ack_timeout_transmitted_hook,
#endif
NULL,
};
static const tx_failed_hook m_tx_failed_hooks[] =
{
#if NRF_802154_CSMA_CA_ENABLED
nrf_802154_csma_ca_tx_failed_hook,
#endif
#if NRF_802154_ACK_TIMEOUT_ENABLED
nrf_802154_ack_timeout_tx_failed_hook,
#endif
NULL,
};
static const tx_started_hook m_tx_started_hooks[] =
{
#if NRF_802154_CSMA_CA_ENABLED
nrf_802154_csma_ca_tx_started_hook,
#endif
#if NRF_802154_ACK_TIMEOUT_ENABLED
nrf_802154_ack_timeout_tx_started_hook,
#endif
NULL,
};
static const rx_started_hook m_rx_started_hooks[] =
{
#if NRF_802154_DELAYED_TRX_ENABLED
nrf_802154_delayed_trx_rx_started_hook,
#endif
NULL,
};
bool nrf_802154_core_hooks_terminate(nrf_802154_term_t term_lvl, req_originator_t req_orig)
{
bool result = true;
for (uint32_t i = 0; i < sizeof(m_abort_hooks) / sizeof(m_abort_hooks[0]); i++)
{
if (m_abort_hooks[i] == NULL)
{
break;
}
result = m_abort_hooks[i](term_lvl, req_orig);
if (!result)
{
break;
}
}
return result;
}
void nrf_802154_core_hooks_transmitted(const uint8_t * p_frame)
{
for (uint32_t i = 0; i < sizeof(m_transmitted_hooks) / sizeof(m_transmitted_hooks[0]); i++)
{
if (m_transmitted_hooks[i] == NULL)
{
break;
}
m_transmitted_hooks[i](p_frame);
}
}
bool nrf_802154_core_hooks_tx_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
bool result = true;
for (uint32_t i = 0; i < sizeof(m_tx_failed_hooks) / sizeof(m_tx_failed_hooks[0]); i++)
{
if (m_tx_failed_hooks[i] == NULL)
{
break;
}
result = m_tx_failed_hooks[i](p_frame, error);
if (!result)
{
break;
}
}
return result;
}
bool nrf_802154_core_hooks_tx_started(const uint8_t * p_frame)
{
bool result = true;
for (uint32_t i = 0; i < sizeof(m_tx_started_hooks) / sizeof(m_tx_started_hooks[0]); i++)
{
if (m_tx_started_hooks[i] == NULL)
{
break;
}
result = m_tx_started_hooks[i](p_frame);
if (!result)
{
break;
}
}
return result;
}
void nrf_802154_core_hooks_rx_started(void)
{
for (uint32_t i = 0; i < sizeof(m_rx_started_hooks) / sizeof(m_rx_started_hooks[0]); i++)
{
if (m_rx_started_hooks[i] == NULL)
{
break;
}
m_rx_started_hooks[i]();
}
}

View file

@ -1,100 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_CORE_HOOKS_H__
#define NRF_802154_CORE_HOOKS_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_const.h"
#include "nrf_802154_types.h"
/**
* @defgroup nrf_802154_hooks Hooks for the 802.15.4 driver core
* @{
* @ingroup nrf_802154
* @brief Hooks for the 802.15.4 driver core module.
*
* Hooks are used by optional driver features to modify way in which notifications are propagated
* through the driver.
*/
/**
* @brief Process hooks for the terminate request.
*
* @param[in] term_lvl Termination level of request that terminates current operation.
* @param[in] req_orig Module that originates this request.
*
* @retval true All procedures are aborted.
* @retval false There is ongoing procedure that cannot be aborted due to too low @p priority.
*/
bool nrf_802154_core_hooks_terminate(nrf_802154_term_t term_lvl, req_originator_t req_orig);
/**
* @brief Process hooks for the transmitted event.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that was transmitted.
*/
void nrf_802154_core_hooks_transmitted(const uint8_t * p_frame);
/**
* @brief Process hooks for the TX failed event.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that was not transmitted.
* @param[in] error Cause of failed transmission.
*
* @retval true TX failed event should be propagated to the MAC layer.
* @retval false TX failed event should not be propagated to the MAC layer. It is handled
* internally.
*/
bool nrf_802154_core_hooks_tx_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error);
/**
* @brief Process hooks for the TX started event.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that is being transmitted.
*
* @retval true TX started event should be propagated to the MAC layer.
* @retval false TX started event should not be propagated to the MAC layer. It is handled
* internally.
*/
bool nrf_802154_core_hooks_tx_started(const uint8_t * p_frame);
/**
* @brief Process hooks for the RX started event.
*/
void nrf_802154_core_hooks_rx_started(void);
/**
*@}
**/
#endif // NRF_802154_CORE_HOOKS_H__

View file

@ -1,285 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements critical sections used with requests by 802.15.4 driver.
*
*/
#include "nrf_802154_critical_section.h"
#include <assert.h>
#include <stdint.h>
#include "nrf_802154_config.h"
#include "nrf_802154_debug.h"
#include "nrf_802154_rsch.h"
#include "hal/nrf_radio.h"
#include "platform/lp_timer/nrf_802154_lp_timer.h"
#include <nrf.h>
#define CMSIS_IRQ_NUM_VECTACTIVE_DIFF 16
#define NESTED_CRITICAL_SECTION_ALLOWED_PRIORITY_NONE (-1)
static volatile uint8_t m_critical_section_monitor; ///< Monitors each critical section enter operation
static volatile uint8_t m_nested_critical_section_counter; ///< Counter of nested critical sections
static volatile int8_t m_nested_critical_section_allowed_priority; ///< Indicator if nested critical sections are currently allowed
/***************************************************************************************************
* @section Critical sections management
**************************************************************************************************/
/** @brief Enter critical section for RADIO peripheral
*
* @note RADIO peripheral registers (and NVIC) are modified only when timeslot is granted for the
* 802.15.4 driver.
*/
static void radio_critical_section_enter(void)
{
if (nrf_802154_rsch_prec_is_approved(RSCH_PREC_RAAL, RSCH_PRIO_MIN_APPROVED))
{
NVIC_DisableIRQ(RADIO_IRQn);
}
}
/** @brief Exit critical section for RADIO peripheral
*
* @note RADIO peripheral registers (and NVIC) are modified only when timeslot is granted for the
* 802.15.4 driver.
*/
static void radio_critical_section_exit(void)
{
if (nrf_802154_rsch_prec_is_approved(RSCH_PREC_RAAL, RSCH_PRIO_MIN_APPROVED))
{
NVIC_EnableIRQ(RADIO_IRQn);
}
}
/** @brief Convert active priority value to int8_t type.
*
* @param[in] active_priority Active priority in uint32_t format
*
* @return Active_priority value in int8_t format.
*/
static int8_t active_priority_convert(uint32_t active_priority)
{
return active_priority == UINT32_MAX ? INT8_MAX : (int8_t)active_priority;
}
/** @brief Check if active vector priority is equal to priority that allows nested crit sections.
*
* @retval true Active vector priority allows nested critical sections.
* @retval false Active vector priority denies nested critical sections.
*/
static bool nested_critical_section_is_allowed_in_this_context(void)
{
return m_nested_critical_section_allowed_priority ==
active_priority_convert(nrf_802154_critical_section_active_vector_priority_get());
}
static bool critical_section_enter(bool forced)
{
bool result = false;
uint8_t cnt;
if (forced ||
(m_nested_critical_section_counter == 0) ||
nested_critical_section_is_allowed_in_this_context())
{
do
{
cnt = __LDREXB(&m_nested_critical_section_counter);
assert(cnt < UINT8_MAX);
}
while (__STREXB(cnt + 1, &m_nested_critical_section_counter));
nrf_802154_critical_section_rsch_enter();
nrf_802154_lp_timer_critical_section_enter();
radio_critical_section_enter();
__DSB();
__ISB();
m_critical_section_monitor++;
result = true;
}
return result;
}
static void critical_section_exit(void)
{
uint8_t cnt = m_nested_critical_section_counter;
uint8_t monitor;
uint8_t atomic_cnt;
static bool exiting_crit_sect;
bool result;
assert(cnt > 0);
do
{
monitor = m_critical_section_monitor;
// If critical section is not nested exit critical section
if (cnt == 1)
{
assert(!exiting_crit_sect);
(void)exiting_crit_sect;
exiting_crit_sect = true;
nrf_802154_critical_section_rsch_exit();
radio_critical_section_exit();
nrf_802154_lp_timer_critical_section_exit();
exiting_crit_sect = false;
}
do
{
atomic_cnt = __LDREXB(&m_nested_critical_section_counter);
assert(atomic_cnt == cnt);
}
while (__STREXB(atomic_cnt - 1, &m_nested_critical_section_counter));
// If critical section is not nested verify if during exit procedure RSCH notified
// change of state or critical section was visited by higher priority IRQ meantime.
if (cnt == 1)
{
// Check if critical section must be exited again.
if (nrf_802154_critical_section_rsch_event_is_pending() ||
(monitor != m_critical_section_monitor))
{
result = critical_section_enter(false);
assert(result);
(void)result;
continue;
}
else
{
break;
}
}
}
while (cnt == 1);
}
/***************************************************************************************************
* @section API functions
**************************************************************************************************/
void nrf_802154_critical_section_init(void)
{
m_nested_critical_section_counter = 0;
m_nested_critical_section_allowed_priority = NESTED_CRITICAL_SECTION_ALLOWED_PRIORITY_NONE;
}
bool nrf_802154_critical_section_enter(void)
{
bool result;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CRIT_SECT_ENTER);
result = critical_section_enter(false);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CRIT_SECT_ENTER);
return result;
}
void nrf_802154_critical_section_forcefully_enter(void)
{
bool critical_section_entered;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CRIT_SECT_ENTER);
critical_section_entered = critical_section_enter(true);
assert(critical_section_entered);
(void)critical_section_entered;
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CRIT_SECT_ENTER);
}
void nrf_802154_critical_section_exit(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_CRIT_SECT_EXIT);
critical_section_exit();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_CRIT_SECT_EXIT);
}
void nrf_802154_critical_section_nesting_allow(void)
{
assert(m_nested_critical_section_allowed_priority ==
NESTED_CRITICAL_SECTION_ALLOWED_PRIORITY_NONE);
assert(m_nested_critical_section_counter >= 1);
m_nested_critical_section_allowed_priority = active_priority_convert(
nrf_802154_critical_section_active_vector_priority_get());
}
void nrf_802154_critical_section_nesting_deny(void)
{
assert(m_nested_critical_section_allowed_priority >= 0);
assert(m_nested_critical_section_counter >= 1);
m_nested_critical_section_allowed_priority = NESTED_CRITICAL_SECTION_ALLOWED_PRIORITY_NONE;
}
bool nrf_802154_critical_section_is_nested(void)
{
return m_nested_critical_section_counter > 1;
}
uint32_t nrf_802154_critical_section_active_vector_priority_get(void)
{
uint32_t active_vector_id = (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) >> SCB_ICSR_VECTACTIVE_Pos;
IRQn_Type irq_number;
uint32_t active_priority;
// Check if this function is called from main thread.
if (active_vector_id == 0)
{
return UINT32_MAX;
}
assert(active_vector_id >= CMSIS_IRQ_NUM_VECTACTIVE_DIFF);
irq_number = (IRQn_Type)(active_vector_id - CMSIS_IRQ_NUM_VECTACTIVE_DIFF);
active_priority = NVIC_GetPriority(irq_number);
return active_priority;
}

View file

@ -1,130 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_CRITICAL_SECTION_H__
#define NRF_802154_CRITICAL_SECTION_H__
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_critical_section 802.15.4 driver critical section
* @{
* @ingroup nrf_802154
* @brief Critical section used with requests to the 802.15.4 driver.
*/
/**
* @brief Initialize critical section module.
*/
void nrf_802154_critical_section_init(void);
/**
* @brief Enter critical section in the 802.15.4 driver.
*
* @note Entering critical section may be prohibited at given time. If critical section is not
* entered, request should not be proceeded.
*
* @retval true Entered critical section.
* @retval false Could not enter critical section.
*/
bool nrf_802154_critical_section_enter(void);
/**
* @brief Exit critical section in the 802.15.4 driver.
*/
void nrf_802154_critical_section_exit(void);
/**
* @brief Forcefully enter critical section in the 802.15.4 driver.
*
* This function enters critical section regardless critical sections is already entered.
*
* This function is intended to be used by RADIO IRQ handler and RAAL notifications handlers to
* prevent interrupting of these procedures by FSM requests from higher priority IRQ handlers.
*/
void nrf_802154_critical_section_forcefully_enter(void);
/**
* @brief Allow entering nested critical section.
*
* This function is intended to be used with notification module in order to allow processing
* requests called from notification context.
*/
void nrf_802154_critical_section_nesting_allow(void);
/**
* @brief Disallow entering nested critical section.
*/
void nrf_802154_critical_section_nesting_deny(void);
/**
* @brief Check if critical section is nested.
*
* @retval true Critical section is nested.
* @retval false Critical section is not nested.
*/
bool nrf_802154_critical_section_is_nested(void);
/**
* @brief Get current IRQ priority.
*
* @return IRQ priority
*/
uint32_t nrf_802154_critical_section_active_vector_priority_get(void);
/**
* @brief Function called to enter critical section in the RSCH module.
*/
extern void nrf_802154_critical_section_rsch_enter(void);
/**
* @brief Function called to exit critical section in the RSCH module.
*/
extern void nrf_802154_critical_section_rsch_exit(void);
/**
* @brief Check if there is pending event in the RSCH critical section.
*/
extern bool nrf_802154_critical_section_rsch_event_is_pending(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_802154_CRITICAL_SECTION_H__

View file

@ -1,192 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements debug helpers for the nRF 802.15.4 radio driver.
*
*/
#include "nrf_802154_debug.h"
#include <stdint.h>
#include "hal/nrf_gpio.h"
#include "hal/nrf_gpiote.h"
#include "hal/nrf_ppi.h"
#include "nrf.h"
#if ENABLE_DEBUG_LOG
/// Buffer used to store debug log messages.
volatile uint32_t nrf_802154_debug_log_buffer[NRF_802154_DEBUG_LOG_BUFFER_LEN];
/// Index of the log buffer pointing to the element that should be filled with next log message.
volatile uint32_t nrf_802154_debug_log_ptr = 0;
#endif
#if ENABLE_DEBUG_GPIO
/**
* @brief Initialize PPI to toggle GPIO pins on radio events.
*/
static void radio_event_gpio_toggle_init(void)
{
nrf_gpio_cfg_output(PIN_DBG_RADIO_EVT_END);
nrf_gpio_cfg_output(PIN_DBG_RADIO_EVT_DISABLED);
nrf_gpio_cfg_output(PIN_DBG_RADIO_EVT_READY);
nrf_gpio_cfg_output(PIN_DBG_RADIO_EVT_FRAMESTART);
nrf_gpio_cfg_output(PIN_DBG_RADIO_EVT_EDEND);
nrf_gpio_cfg_output(PIN_DBG_RADIO_EVT_PHYEND);
nrf_gpiote_task_configure(0,
PIN_DBG_RADIO_EVT_END,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_configure(1,
PIN_DBG_RADIO_EVT_DISABLED,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_configure(2,
PIN_DBG_RADIO_EVT_READY,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_configure(3,
PIN_DBG_RADIO_EVT_FRAMESTART,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_configure(4,
PIN_DBG_RADIO_EVT_EDEND,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_configure(5,
PIN_DBG_RADIO_EVT_PHYEND,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_enable(0);
nrf_gpiote_task_enable(1);
nrf_gpiote_task_enable(2);
nrf_gpiote_task_enable(3);
nrf_gpiote_task_enable(4);
nrf_gpiote_task_enable(5);
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL0,
(uint32_t)&NRF_RADIO->EVENTS_END,
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_0));
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL1,
(uint32_t)&NRF_RADIO->EVENTS_DISABLED,
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_1));
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL2,
(uint32_t)&NRF_RADIO->EVENTS_READY,
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_2));
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL3,
(uint32_t)&NRF_RADIO->EVENTS_FRAMESTART,
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_3));
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL4,
(uint32_t)&NRF_RADIO->EVENTS_EDEND,
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_4));
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL5,
(uint32_t)&NRF_RADIO->EVENTS_PHYEND,
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_5));
nrf_ppi_channel_enable(NRF_PPI_CHANNEL0);
nrf_ppi_channel_enable(NRF_PPI_CHANNEL1);
nrf_ppi_channel_enable(NRF_PPI_CHANNEL2);
nrf_ppi_channel_enable(NRF_PPI_CHANNEL3);
nrf_ppi_channel_enable(NRF_PPI_CHANNEL4);
nrf_ppi_channel_enable(NRF_PPI_CHANNEL5);
}
/**
* @brief Initialize GPIO to set it simulated arbiter events.
*/
static void raal_simulator_gpio_init(void)
{
#if RAAL_SIMULATOR
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_ACTIVE);
nrf_gpio_cfg_output(PIN_DBG_RAAL_CRITICAL_SECTION);
#endif
}
/**
* @brief Initialize PPI to toggle GPIO pins on Softdevice events. Initialize GPIO to set it
* according to Softdevice arbiter client events.
*/
static void raal_softdevice_event_gpio_toggle_init(void)
{
#if RAAL_SOFTDEVICE
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_ACTIVE);
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_EXTEND_REQ);
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_SESSION_IDLE);
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_RADIO_IRQ);
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_FAILED);
nrf_gpio_cfg_output(PIN_DBG_TIMESLOT_BLOCKED);
nrf_gpio_cfg_output(PIN_DBG_RTC0_EVT_REM);
nrf_gpiote_task_configure(5,
PIN_DBG_RTC0_EVT_REM,
NRF_GPIOTE_POLARITY_TOGGLE,
NRF_GPIOTE_INITIAL_VALUE_HIGH);
nrf_gpiote_task_enable(5);
nrf_ppi_channel_endpoint_setup(NRF_PPI_CHANNEL5,
(uint32_t)&NRF_RTC0->EVENTS_COMPARE[1],
nrf_gpiote_task_addr_get(NRF_GPIOTE_TASKS_OUT_5));
nrf_ppi_channel_enable(NRF_PPI_CHANNEL5);
#endif // RAAL_SOFTDEVICE
}
#endif // ENABLE_DEBUG_GPIO
void nrf_802154_debug_init(void)
{
#if ENABLE_DEBUG_GPIO
radio_event_gpio_toggle_init();
raal_simulator_gpio_init();
raal_softdevice_event_gpio_toggle_init();
#endif // ENABLE_DEBUG_GPIO
}
#if ENABLE_DEBUG_ASSERT
void __assert_func(const char * file, int line, const char * func, const char * cond)
{
(void)file;
(void)line;
(void)func;
(void)cond;
__disable_irq();
while (1)
;
}
#endif // ENABLE_DEBUG_ASSERT

View file

@ -1,196 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module contains debug helpers for 802.15.4 radio driver for nRF SoC devices.
*
*/
#ifndef NRF_802154_DEBUG_H_
#define NRF_802154_DEBUG_H_
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
#define NRF_802154_DEBUG_LOG_BUFFER_LEN 1024
#define EVENT_TRACE_ENTER 0x0001UL
#define EVENT_TRACE_EXIT 0x0002UL
#define EVENT_SET_STATE 0x0005UL
#define EVENT_RADIO_RESET 0x0006UL
#define EVENT_TIMESLOT_REQUEST 0x0007UL
#define EVENT_TIMESLOT_REQUEST_RESULT 0x0008UL
#define FUNCTION_SLEEP 0x0001UL
#define FUNCTION_RECEIVE 0x0002UL
#define FUNCTION_TRANSMIT 0x0003UL
#define FUNCTION_ENERGY_DETECTION 0x0004UL
#define FUNCTION_BUFFER_FREE 0x0005UL
#define FUNCTION_CCA 0x0006UL
#define FUNCTION_CONTINUOUS_CARRIER 0x0007UL
#define FUNCTION_CSMACA 0x0008UL
#define FUNCTION_TRANSMIT_AT 0x0009UL
#define FUNCTION_RECEIVE_AT 0x000AUL
#define FUNCTION_IRQ_HANDLER 0x0100UL
#define FUNCTION_EVENT_FRAMESTART 0x0101UL
#define FUNCTION_EVENT_BCMATCH 0x0102UL
#define FUNCTION_EVENT_END 0x0103UL
#define FUNCTION_EVENT_DISABLED 0x0104UL
#define FUNCTION_EVENT_READY 0x0105UL
#define FUNCTION_EVENT_CCAIDLE 0x0106UL
#define FUNCTION_EVENT_CCABUSY 0x0107UL
#define FUNCTION_EVENT_EDEND 0x0108UL
#define FUNCTION_EVENT_PHYEND 0x0109UL
#define FUNCTION_EVENT_CRCOK 0x010AUL
#define FUNCTION_EVENT_CRCERROR 0x010BUL
#define FUNCTION_AUTO_ACK_ABORT 0x0201UL
#define FUNCTION_TIMESLOT_STARTED 0x0202UL
#define FUNCTION_TIMESLOT_ENDED 0x0203UL
#define FUNCTION_CRIT_SECT_ENTER 0x0204UL
#define FUNCTION_CRIT_SECT_EXIT 0x0205UL
#define FUNCTION_RAAL_CRIT_SECT_ENTER 0x0301UL
#define FUNCTION_RAAL_CRIT_SECT_EXIT 0x0302UL
#define FUNCTION_RAAL_CONTINUOUS_ENTER 0x0303UL
#define FUNCTION_RAAL_CONTINUOUS_EXIT 0x0304UL
#define FUNCTION_RAAL_SIG_HANDLER 0x0400UL
#define FUNCTION_RAAL_SIG_EVENT_START 0x0401UL
#define FUNCTION_RAAL_SIG_EVENT_MARGIN 0x0402UL
#define FUNCTION_RAAL_SIG_EVENT_EXTEND 0x0403UL
#define FUNCTION_RAAL_SIG_EVENT_ENDED 0x0404UL
#define FUNCTION_RAAL_SIG_EVENT_RADIO 0x0405UL
#define FUNCTION_RAAL_SIG_EVENT_EXTEND_SUCCESS 0x0406UL
#define FUNCTION_RAAL_SIG_EVENT_EXTEND_FAIL 0x0407UL
#define FUNCTION_RAAL_EVT_BLOCKED 0x0408UL
#define FUNCTION_RAAL_EVT_SESSION_IDLE 0x0409UL
#define FUNCTION_RAAL_EVT_HFCLK_READY 0x040AUL
#define FUNCTION_RAAL_SIG_EVENT_MARGIN_MOVE 0x040BUL
#define FUNCTION_RSCH_CONTINUOUS_ENTER 0x0480UL
#define FUNCTION_RSCH_CONTINUOUS_EXIT 0x0481UL
#define FUNCTION_RSCH_CRITICAL_SECTION_ENTER 0x0482UL
#define FUNCTION_RSCH_CRITICAL_SECTION_EXIT 0x0483UL
#define FUNCTION_RSCH_TIMESLOT_STARTED 0x0484UL
#define FUNCTION_RSCH_TIMESLOT_ENDED 0x0485UL
#define FUNCTION_RSCH_PEND_GRANTED 0x0486UL
#define FUNCTION_RSCH_PEND_REVOKED 0x0487UL
#define FUNCTION_RSCH_NOTIFY_GRANTED 0x0488UL
#define FUNCTION_RSCH_NOTIFY_REVOKED 0x0489UL
#define FUNCTION_RSCH_NOTIFY_IF_PENDING 0x048AUL
#define FUNCTION_RSCH_DELAYED_TIMESLOT_REQ 0x048BUL
#define FUNCTION_RSCH_TIMER_DELAYED_PREC 0x048CUL
#define FUNCTION_RSCH_TIMER_DELAYED_START 0x048DUL
#define FUNCTION_CSMA_ABORT 0x0500UL
#define FUNCTION_CSMA_TX_FAILED 0x0501UL
#define FUNCTION_CSMA_TX_STARTED 0x0502UL
#define FUNCTION_CSMA_CHANNEL_BUSY 0x0503UL
#define FUNCTION_CSMA_FRAME_TRANSMIT 0x0504UL
#define FUNCTION_TSCH_ADD 0x0600UL
#define FUNCTION_TSCH_FIRED 0x0601UL
#define PIN_DBG_RADIO_EVT_END 11
#define PIN_DBG_RADIO_EVT_DISABLED 12
#define PIN_DBG_RADIO_EVT_READY 13
#define PIN_DBG_RADIO_EVT_FRAMESTART 14
#define PIN_DBG_RADIO_EVT_EDEND 25
#define PIN_DBG_RADIO_EVT_PHYEND 24
#define PIN_DBG_TIMESLOT_ACTIVE 3
#define PIN_DBG_TIMESLOT_EXTEND_REQ 4
#define PIN_DBG_TIMESLOT_SESSION_IDLE 16
#define PIN_DBG_TIMESLOT_RADIO_IRQ 28
#define PIN_DBG_TIMESLOT_FAILED 29
#define PIN_DBG_TIMESLOT_BLOCKED 30
#define PIN_DBG_RAAL_CRITICAL_SECTION 15
#define PIN_DBG_RTC0_EVT_REM 31
#if ENABLE_DEBUG_LOG
extern volatile uint32_t nrf_802154_debug_log_buffer[
NRF_802154_DEBUG_LOG_BUFFER_LEN];
extern volatile uint32_t nrf_802154_debug_log_ptr;
#define nrf_802154_log(EVENT_CODE, EVENT_ARG) \
do \
{ \
uint32_t ptr = nrf_802154_debug_log_ptr; \
\
nrf_802154_debug_log_buffer[ptr] = ((EVENT_CODE) | ((EVENT_ARG) << 16)); \
nrf_802154_debug_log_ptr = \
ptr < (NRF_802154_DEBUG_LOG_BUFFER_LEN - 1) ? ptr + 1 : 0; \
} \
while (0)
#else // ENABLE_DEBUG_LOG
#define nrf_802154_log(EVENT_CODE, EVENT_ARG) (void)(EVENT_ARG)
#endif // ENABLE_DEBUG_LOG
#if ENABLE_DEBUG_GPIO
#define nrf_802154_pin_set(pin) NRF_P0->OUTSET = (1UL << (pin))
#define nrf_802154_pin_clr(pin) NRF_P0->OUTCLR = (1UL << (pin))
#define nrf_802154_pin_tgl(pin) \
do \
{ \
volatile uint32_t ps = NRF_P0->OUT; \
\
NRF_P0->OUTSET = (~ps & (1UL << (pin))); \
NRF_P0->OUTCLR = (ps & (1UL << (pin))); \
} \
while (0);
#else // ENABLE_DEBUG_GPIO
#define nrf_802154_pin_set(pin)
#define nrf_802154_pin_clr(pin)
#define nrf_802154_pin_tgl(pin)
#endif // ENABLE_DEBUG_GPIO
/**
* @brief Initialize debug helpers for nRF 802.15.4 driver.
*/
void nrf_802154_debug_init(void);
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_DEBUG_H_ */

View file

@ -1,140 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_NOTIFICATION_H__
#define NRF_802154_NOTIFICATION_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_notification 802.15.4 driver notification
* @{
* @ingroup nrf_802154
* @brief Notifications to the next higher layer triggered from 802.15.4 radio driver.
*/
/**
* @brief Function type used for external notification
*
* This function is called instead of default notification. Function is passed to request to notify
* atomically during request processing.
*
* @param[in] result If called request succeeded.
*/
typedef void (* nrf_802154_notification_func_t)(bool result);
/**
* @brief Initialize notification module.
*/
void nrf_802154_notification_init(void);
/**
* @brief Notify next higher layer that a frame was received.
*
* @param[in] p_data Array of bytes containing PSDU. First byte contains frame length, other contain the frame itself.
* @param[in] power RSSI measured during the frame reception.
* @param[in] lqi LQI indicating measured link quality during the frame reception.
*/
void nrf_802154_notify_received(uint8_t * p_data, int8_t power, int8_t lqi);
/**
* @brief Notify next higher layer that reception of a frame failed.
*
* @param[in] error An error code that indicates reason of the failure.
*/
void nrf_802154_notify_receive_failed(nrf_802154_rx_error_t error);
/**
* @brief Notify next higher layer that a frame was transmitted.
*
* @param[in] p_frame Pointer to buffer containing PSDU of transmitted frame.
* @param[in] p_ack Pointer to buffer containing PSDU of ACK frame. NULL if ACK was not
* requested.
* @param[in] power RSSI of received frame or 0 if ACK was not requested.
* @param[in] lqi LQI of received frame of 0 if ACK was not requested.
*/
void nrf_802154_notify_transmitted(const uint8_t * p_frame,
uint8_t * p_ack,
int8_t power,
int8_t lqi);
/**
* @brief Notify next higher layer that a frame was not transmitted.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that failed transmit
* operation.
* @param[in] error An error code indicating reason of the failure.
*/
void nrf_802154_notify_transmit_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error);
/**
* @brief Notify next higher layer that energy detection procedure ended.
*
* @param[in] result Detected energy level.
*/
void nrf_802154_notify_energy_detected(uint8_t result);
/**
* @brief Notify next higher layer that energy detection procedure failed.
*
* @param[in] error An error code indicating reason of the failure.
*/
void nrf_802154_notify_energy_detection_failed(nrf_802154_ed_error_t error);
/**
* @brief Notify next higher layer that CCA procedure ended.
*
* @param[in] is_free If detected that channel is free.
*/
void nrf_802154_notify_cca(bool is_free);
/**
* @brief Notify next higher layer that CCA procedure failed.
*
* @param[in] error An error code indicating reason of the failure.
*/
void nrf_802154_notify_cca_failed(nrf_802154_cca_error_t error);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_802154_NOTIFICATION_H__

View file

@ -1,110 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements notifications triggered directly by the nrf 802.15.4 radio driver.
*
*/
#include "nrf_802154_notification.h"
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154.h"
#include "nrf_802154_critical_section.h"
#define RAW_LENGTH_OFFSET 0
#define RAW_PAYLOAD_OFFSET 1
void nrf_802154_notification_init(void)
{
// Intentionally empty
}
void nrf_802154_notify_received(uint8_t * p_data, int8_t power, int8_t lqi)
{
#if NRF_802154_USE_RAW_API
nrf_802154_received_raw(p_data, power, lqi);
#else // NRF_802154_USE_RAW_API
nrf_802154_received(p_data + RAW_PAYLOAD_OFFSET, p_data[RAW_LENGTH_OFFSET], power, lqi);
#endif // NRF_802154_USE_RAW_API
}
void nrf_802154_notify_receive_failed(nrf_802154_rx_error_t error)
{
nrf_802154_receive_failed(error);
}
void nrf_802154_notify_transmitted(const uint8_t * p_frame,
uint8_t * p_ack,
int8_t power,
int8_t lqi)
{
#if NRF_802154_USE_RAW_API
nrf_802154_transmitted_raw(p_frame, p_ack, power, lqi);
#else // NRF_802154_USE_RAW_API
nrf_802154_transmitted(p_frame + RAW_PAYLOAD_OFFSET,
p_ack == NULL ? NULL : p_ack + RAW_PAYLOAD_OFFSET,
p_ack[RAW_LENGTH_OFFSET],
power,
lqi);
#endif // NRF_802154_USE_RAW_API
}
void nrf_802154_notify_transmit_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
#if NRF_802154_USE_RAW_API
nrf_802154_transmit_failed(p_frame, error);
#else // NRF_802154_USE_RAW_API
nrf_802154_transmit_failed(p_frame + RAW_PAYLOAD_OFFSET, error);
#endif // NRF_802154_USE_RAW_API
}
void nrf_802154_notify_energy_detected(uint8_t result)
{
nrf_802154_energy_detected(result);
}
void nrf_802154_notify_energy_detection_failed(nrf_802154_ed_error_t error)
{
nrf_802154_energy_detection_failed(error);
}
void nrf_802154_notify_cca(bool is_free)
{
nrf_802154_cca_done(is_free);
}
void nrf_802154_notify_cca_failed(nrf_802154_cca_error_t error)
{
nrf_802154_cca_failed(error);
}

View file

@ -1,91 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements notifications triggered by the nrf 802.15.4 radio driver via SWI.
*
*/
#include "nrf_802154_notification.h"
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154.h"
#include "nrf_802154_swi.h"
void nrf_802154_notification_init(void)
{
nrf_802154_swi_init();
}
void nrf_802154_notify_received(uint8_t * p_data, int8_t power, int8_t lqi)
{
nrf_802154_swi_notify_received(p_data, power, lqi);
}
void nrf_802154_notify_receive_failed(nrf_802154_rx_error_t error)
{
nrf_802154_swi_notify_receive_failed(error);
}
void nrf_802154_notify_transmitted(const uint8_t * p_frame,
uint8_t * p_ack,
int8_t power,
int8_t lqi)
{
nrf_802154_swi_notify_transmitted(p_frame, p_ack, power, lqi);
}
void nrf_802154_notify_transmit_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
nrf_802154_swi_notify_transmit_failed(p_frame, error);
}
void nrf_802154_notify_energy_detected(uint8_t result)
{
nrf_802154_swi_notify_energy_detected(result);
}
void nrf_802154_notify_energy_detection_failed(nrf_802154_ed_error_t error)
{
nrf_802154_swi_notify_energy_detection_failed(error);
}
void nrf_802154_notify_cca(bool is_free)
{
nrf_802154_swi_notify_cca(is_free);
}
void nrf_802154_notify_cca_failed(nrf_802154_cca_error_t error)
{
nrf_802154_swi_notify_cca_failed(error);
}

View file

@ -1,209 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements storage of PIB attributes in nRF 802.15.4 radio driver.
*
*/
#include "nrf_802154_pib.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "nrf_802154_config.h"
#include "nrf_802154_const.h"
typedef struct
{
int8_t tx_power; ///< Transmit power.
uint8_t pan_id[PAN_ID_SIZE]; ///< Pan Id of this node.
uint8_t short_addr[SHORT_ADDRESS_SIZE]; ///< Short Address of this node.
uint8_t extended_addr[EXTENDED_ADDRESS_SIZE]; ///< Extended Address of this node.
nrf_802154_cca_cfg_t cca; ///< CCA mode and thresholds.
bool promiscuous : 1; ///< Indicating if radio is in promiscuous mode.
bool auto_ack : 1; ///< Indicating if auto ACK procedure is enabled.
bool pan_coord : 1; ///< Indicating if radio is configured as the PAN coordinator.
uint8_t channel : 5; ///< Channel on which the node receives messages.
} nrf_802154_pib_data_t;
// Static variables.
static nrf_802154_pib_data_t m_data; ///< Buffer containing PIB data.
void nrf_802154_pib_init(void)
{
m_data.promiscuous = false;
m_data.auto_ack = true;
m_data.pan_coord = false;
m_data.channel = 11;
memset(m_data.pan_id, 0xff, sizeof(m_data.pan_id));
m_data.short_addr[0] = 0xfe;
m_data.short_addr[1] = 0xff;
memset(m_data.extended_addr, 0, sizeof(m_data.extended_addr));
m_data.cca.mode = NRF_802154_CCA_MODE_DEFAULT;
m_data.cca.ed_threshold = NRF_802154_CCA_ED_THRESHOLD_DEFAULT;
m_data.cca.corr_threshold = NRF_802154_CCA_CORR_THRESHOLD_DEFAULT;
m_data.cca.corr_limit = NRF_802154_CCA_CORR_LIMIT_DEFAULT;
}
bool nrf_802154_pib_promiscuous_get(void)
{
return m_data.promiscuous;
}
void nrf_802154_pib_promiscuous_set(bool enabled)
{
m_data.promiscuous = enabled;
}
bool nrf_802154_pib_auto_ack_get(void)
{
return m_data.auto_ack;
}
void nrf_802154_pib_auto_ack_set(bool enabled)
{
m_data.auto_ack = enabled;
}
bool nrf_802154_pib_pan_coord_get(void)
{
return m_data.pan_coord;
}
void nrf_802154_pib_pan_coord_set(bool enabled)
{
m_data.pan_coord = enabled;
}
uint8_t nrf_802154_pib_channel_get(void)
{
return m_data.channel;
}
void nrf_802154_pib_channel_set(uint8_t channel)
{
m_data.channel = channel;
}
int8_t nrf_802154_pib_tx_power_get(void)
{
return m_data.tx_power;
}
void nrf_802154_pib_tx_power_set(int8_t dbm)
{
const int8_t allowed_values[] = {-40, -20, -16, -12, -8, -4, 0, 2, 3, 4, 5, 6, 7, 8};
const int8_t highest_value =
allowed_values[(sizeof(allowed_values) / sizeof(allowed_values[0])) - 1];
if (dbm > highest_value)
{
dbm = highest_value;
}
else
{
for (uint32_t i = 0; i < sizeof(allowed_values) / sizeof(allowed_values[0]); i++)
{
if (dbm <= allowed_values[i])
{
dbm = allowed_values[i];
break;
}
}
}
m_data.tx_power = dbm;
}
const uint8_t * nrf_802154_pib_pan_id_get(void)
{
return m_data.pan_id;
}
void nrf_802154_pib_pan_id_set(const uint8_t * p_pan_id)
{
memcpy(m_data.pan_id, p_pan_id, PAN_ID_SIZE);
}
const uint8_t * nrf_802154_pib_extended_address_get(void)
{
return m_data.extended_addr;
}
void nrf_802154_pib_extended_address_set(const uint8_t * p_extended_address)
{
memcpy(m_data.extended_addr, p_extended_address, EXTENDED_ADDRESS_SIZE);
}
const uint8_t * nrf_802154_pib_short_address_get(void)
{
return m_data.short_addr;
}
void nrf_802154_pib_short_address_set(const uint8_t * p_short_address)
{
memcpy(m_data.short_addr, p_short_address, SHORT_ADDRESS_SIZE);
}
void nrf_802154_pib_cca_cfg_set(const nrf_802154_cca_cfg_t * p_cca_cfg)
{
switch (p_cca_cfg->mode)
{
case NRF_RADIO_CCA_MODE_ED:
m_data.cca.mode = p_cca_cfg->mode;
m_data.cca.ed_threshold = p_cca_cfg->ed_threshold;
break;
case NRF_RADIO_CCA_MODE_CARRIER:
m_data.cca.mode = p_cca_cfg->mode;
m_data.cca.corr_threshold = p_cca_cfg->corr_threshold;
m_data.cca.corr_limit = p_cca_cfg->corr_limit;
break;
case NRF_RADIO_CCA_MODE_CARRIER_AND_ED:
case NRF_RADIO_CCA_MODE_CARRIER_OR_ED:
memcpy(&m_data.cca, p_cca_cfg, sizeof(m_data.cca));
break;
default:
assert(false);
}
}
void nrf_802154_pib_cca_cfg_get(nrf_802154_cca_cfg_t * p_cca_cfg)
{
memcpy(p_cca_cfg, &m_data.cca, sizeof(m_data.cca));
}

View file

@ -1,192 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This file implements storage of PIB attributes in nRF 802.15.4 radio driver.
*
*/
#ifndef NRF_802154_PIB_H_
#define NRF_802154_PIB_H_
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Initialize this module.
*/
void nrf_802154_pib_init(void);
/**
* @brief Check if promiscuous mode is enabled.
*
* @retval true If promiscuous mode is enabled.
* @retval false If promiscuous mode is disabled.
*/
bool nrf_802154_pib_promiscuous_get(void);
/**
* @brief Enable or disable promiscuous mode.
*
* @param[in] enabled If promiscuous mode should be enabled.
*/
void nrf_802154_pib_promiscuous_set(bool enabled);
/**
* @brief Check if auto ACK procedure is enabled.
*
* @retval true If auto ACK procedure is enabled.
* @retval false If auto ACK procedure is disabled.
*/
bool nrf_802154_pib_auto_ack_get(void);
/**
* @brief Enable or disable auto ACK procedure.
*
* @param[in] enabled If auto ACK procedure should be enabled.
*/
void nrf_802154_pib_auto_ack_set(bool enabled);
/**
* @brief Check if radio is configured as the PAN coordinator.
*
* @retval true If radio is configured as the PAN coordinator.
* @retval false If radio is not configured as the PAN coordinator.
*/
bool nrf_802154_pib_pan_coord_get(void);
/**
* @brief Notify driver that radio is configured as the PAN coordinator.
*
* @param[in] enabled If radio is configured as the PAN coordinator.
*/
void nrf_802154_pib_pan_coord_set(bool enabled);
/**
* @brief Get currently used channel.
*
* @return Channel number used by the driver.
*/
uint8_t nrf_802154_pib_channel_get(void);
/**
* @brief Set channel that will be used by the driver.
*
* @param[in] channel Number of channel used by the driver.
*/
void nrf_802154_pib_channel_set(uint8_t channel);
/**
* @brief Get transmit power.
*
* @returns Transmit power [dBm].
*/
int8_t nrf_802154_pib_tx_power_get(void);
/**
* @brief Set transmit power used for ACK frames.
*
* @param[in] dbm Transmit power [dBm].
*/
void nrf_802154_pib_tx_power_set(int8_t dbm);
/**
* @brief Get PAN Id used by this device.
*
* @returns Pointer to buffer containing PAN Id value (2 bytes, little-endian).
*/
const uint8_t * nrf_802154_pib_pan_id_get(void);
/**
* @brief Set PAN Id used by this device.
*
* @param[in] p_pan_id Pointer to PAN Id (2 bytes, little-endian).
*
* This function makes copy of the PAN Id.
*/
void nrf_802154_pib_pan_id_set(const uint8_t * p_pan_id);
/**
* @brief Get Extended Address of this device
*
* @returns Pointer to buffer containing extended address (8 bytes, little-endian).
*/
const uint8_t * nrf_802154_pib_extended_address_get(void);
/**
* @brief Set Extended Address of this device.
*
* @param[in] p_extended_address Pointer to extended address (8 bytes, little-endian).
*
* This function makes copy of the address.
*/
void nrf_802154_pib_extended_address_set(const uint8_t * p_extended_address);
/**
* @brief Get Short Address of this device
*
* @returns Pointer to buffer containing short address (2 bytes, little-endian).
*/
const uint8_t * nrf_802154_pib_short_address_get(void);
/**
* @brief Set Short Address of this device.
*
* @param[in] p_short_address Pointer to short address (2 bytes, little-endian).
*
* This function makes copy of the address.
*/
void nrf_802154_pib_short_address_set(const uint8_t * p_short_address);
/**
* @brief Set radio CCA mode and threshold.
*
* @param[in] p_cca_cfg A pointer to the CCA configuration structure. Only fields relevant to selected mode are updated.
*/
void nrf_802154_pib_cca_cfg_set(const nrf_802154_cca_cfg_t * p_cca_cfg);
/**
* @brief Get current radio CCA configuration.
*
* @param[out] p_cca_cfg A pointer to the structure for current CCA configuration.
*/
void nrf_802154_pib_cca_cfg_get(nrf_802154_cca_cfg_t * p_cca_cfg);
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_PIB_H_ */

View file

@ -1,76 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_PRIORITY_DROP_H__
#define NRF_802154_PRIORITY_DROP_H__
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_priority_drop 802.15.4 driver procedures with lower priority.
* @{
* @ingroup nrf_802154
* @brief Internal procedures of 802.15.4 driver that should be called with lower priority than
* the caller's priority.
*/
/**
* @brief Initialize notification module.
*/
void nrf_802154_priority_drop_init(void);
/**
* @brief Request stop of the high frequency clock.
*
* @note This function should be called through this module to prevent calling it from the arbiter
* context.
*/
void nrf_802154_priority_drop_hfclk_stop(void);
/**
* @brief Terminate requesting of high frequency clock stop.
*
* Function used to to terminate HFClk stop procedure requested by previous call to
* @rev nrf_802154_priority_drop_hfclk_stop. The HFClk stop procedure is terminated only if it has
* not been started.
*/
void nrf_802154_priority_drop_hfclk_stop_terminate(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_802154_PRIORITY_DROP_H__

View file

@ -1,56 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements procedures that should be called with lower priority than caller in
* the nrf 802.15.4 radio driver.
*
*/
#include "nrf_802154_priority_drop.h"
#include "platform/clock/nrf_802154_clock.h"
void nrf_802154_priority_drop_init(void)
{
// Intentionally empty
}
void nrf_802154_priority_drop_hfclk_stop(void)
{
nrf_802154_clock_hfclk_stop();
}
void nrf_802154_priority_drop_hfclk_stop_terminate(void)
{
// Intentionally empty:
// nrf_802154_priority_drop_hfclk_stop is synchronous and cannot be terminated.
}

View file

@ -1,55 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements procedures that should be called with lower priority than caller in
* the nrf 802.15.4 radio driver.
*
*/
#include "nrf_802154_priority_drop.h"
#include "nrf_802154_swi.h"
void nrf_802154_priority_drop_init(void)
{
nrf_802154_swi_init();
}
void nrf_802154_priority_drop_hfclk_stop(void)
{
nrf_802154_swi_hfclk_stop();
}
void nrf_802154_priority_drop_hfclk_stop_terminate(void)
{
nrf_802154_swi_hfclk_stop_terminate();
}

View file

@ -1,160 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module contains calculations of 802.15.4 radio driver procedures duration.
*
*/
#ifndef NRF_802154_PROCEDURES_DURATION_H_
#define NRF_802154_PROCEDURES_DURATION_H_
#include <stdbool.h>
#include <stdint.h>
#include "nrf.h"
#include "nrf_802154_const.h"
#define TX_RAMP_UP_TIME 40 // us
#define RX_RAMP_UP_TIME 40 // us
#define RX_RAMP_DOWN_TIME 0 // us
#define MAX_RAMP_DOWN_TIME 6 // us
#define RX_TX_TURNAROUND_TIME 20 // us
#define A_CCA_DURATION_SYMBOLS 8 // sym
#define A_TURNAROUND_TIME_SYMBOLS 12 // sym
#define A_UNIT_BACKOFF_SYMBOLS 20 // sym
#define PHY_SYMBOLS_FROM_OCTETS(octets) ((octets) * PHY_SYMBOLS_PER_OCTET)
#define PHY_US_TIME_FROM_SYMBOLS(symbols) ((symbols) * PHY_US_PER_SYMBOL)
#define IMM_ACK_SYMBOLS (PHY_SHR_SYMBOLS + \
PHY_SYMBOLS_FROM_OCTETS(IMM_ACK_LENGTH + PHR_SIZE))
#define IMM_ACK_DURATION (PHY_US_TIME_FROM_SYMBOLS(IMM_ACK_SYMBOLS))
#define MAC_IMM_ACK_WAIT_SYMBOLS (A_UNIT_BACKOFF_SYMBOLS + \
A_TURNAROUND_TIME_SYMBOLS + \
IMM_ACK_SYMBOLS)
__STATIC_INLINE uint16_t nrf_802154_tx_duration_get(uint8_t psdu_length,
bool cca,
bool ack_requested);
__STATIC_INLINE uint16_t nrf_802154_cca_before_tx_duration_get(void);
__STATIC_INLINE uint16_t nrf_802154_rx_duration_get(uint8_t psdu_length, bool ack_requested);
__STATIC_INLINE uint16_t nrf_802154_cca_duration_get(void);
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE uint16_t nrf_802154_frame_duration_get(uint8_t psdu_length,
bool shr,
bool phr)
{
uint16_t us_time = PHY_US_TIME_FROM_SYMBOLS(PHY_SYMBOLS_FROM_OCTETS(psdu_length));
if (phr)
{
us_time += PHY_US_TIME_FROM_SYMBOLS(PHY_SYMBOLS_FROM_OCTETS(PHR_SIZE));
}
if (shr)
{
us_time += PHY_US_TIME_FROM_SYMBOLS(PHY_SHR_SYMBOLS);
}
return us_time;
}
__STATIC_INLINE uint16_t nrf_802154_tx_duration_get(uint8_t psdu_length,
bool cca,
bool ack_requested)
{
// ramp down
// if CCA: + RX ramp up + CCA + RX ramp down
// + TX ramp up + SHR + PHR + PSDU
// if ACK: + macAckWaitDuration
uint16_t us_time = MAX_RAMP_DOWN_TIME + TX_RAMP_UP_TIME + nrf_802154_frame_duration_get(
psdu_length,
true,
true);
if (ack_requested)
{
us_time += PHY_US_TIME_FROM_SYMBOLS(MAC_IMM_ACK_WAIT_SYMBOLS);
}
if (cca)
{
us_time += RX_RAMP_UP_TIME + RX_RAMP_DOWN_TIME + PHY_US_TIME_FROM_SYMBOLS(
A_CCA_DURATION_SYMBOLS);
}
return us_time;
}
__STATIC_INLINE uint16_t nrf_802154_cca_before_tx_duration_get(void)
{
// CCA + turnaround time
uint16_t us_time = PHY_US_TIME_FROM_SYMBOLS(A_CCA_DURATION_SYMBOLS) + RX_TX_TURNAROUND_TIME;
return us_time;
}
__STATIC_INLINE uint16_t nrf_802154_rx_duration_get(uint8_t psdu_length, bool ack_requested)
{
// SHR + PHR + PSDU
// if ACK: + aTurnaroundTime + ACK frame duration
uint16_t us_time = nrf_802154_frame_duration_get(psdu_length, true, true);
if (ack_requested)
{
us_time += PHY_US_TIME_FROM_SYMBOLS(A_TURNAROUND_TIME_SYMBOLS +
PHY_SHR_SYMBOLS +
PHY_SYMBOLS_FROM_OCTETS(IMM_ACK_LENGTH + PHR_SIZE));
}
return us_time;
}
__STATIC_INLINE uint16_t nrf_802154_cca_duration_get(void)
{
// ramp down + rx ramp up + CCA
uint16_t us_time = MAX_RAMP_DOWN_TIME +
RX_RAMP_UP_TIME +
PHY_US_TIME_FROM_SYMBOLS(A_CCA_DURATION_SYMBOLS);
return us_time;
}
#endif /* SUPPRESS_INLINE_IMPLEMENTATION */
#endif /* NRF_802154_PROCEDURES_DURATION_H_ */

View file

@ -1,161 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_REQUEST_H__
#define NRF_802154_REQUEST_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_const.h"
#include "nrf_802154_notification.h"
#include "nrf_802154_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_request 802.15.4 driver request
* @{
* @ingroup nrf_802154
* @brief Requests to the driver triggered from the MAC layer.
*/
/**
* @brief Initialize request module.
*/
void nrf_802154_request_init(void);
/**
* @brief Request entering sleep state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
*
* @retval true The driver will enter sleep state.
* @retval false The driver cannot enter sleep state due to ongoing operation.
*/
bool nrf_802154_request_sleep(nrf_802154_term_t term_lvl);
/**
* @brief Request entering receive state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @param[in] notify_function Function called to notify status of this procedure. May be NULL.
* @param[in] notify_abort If abort notification should be triggered automatically.
*
* @retval true The driver will enter receive state.
* @retval false The driver cannot enter receive state due to ongoing operation.
*/
bool nrf_802154_request_receive(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
nrf_802154_notification_func_t notify_function,
bool notify_abort);
/**
* @brief Request entering transmit state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @param[in] p_data Pointer to the frame to transmit.
* @param[in] cca If the driver should perform CCA procedure before transmission.
* @param[in] immediate If true, the driver schedules transmission immediately or never;
* if false transmission may be postponed until tx preconditions are
* met.
* @param[in] notify_function Function called to notify status of this procedure. May be NULL.
*
* @retval true The driver will enter transmit state.
* @retval false The driver cannot enter transmit state due to ongoing operation.
*/
bool nrf_802154_request_transmit(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
const uint8_t * p_data,
bool cca,
bool immediate,
nrf_802154_notification_func_t notify_function);
/**
* @brief Request entering energy detection state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] time_us Requested duration of energy detection procedure.
*
* @retval true The driver will enter energy detection state.
* @retval false The driver cannot enter energy detection state due to ongoing operation.
*/
bool nrf_802154_request_energy_detection(nrf_802154_term_t term_lvl, uint32_t time_us);
/**
* @brief Request entering CCA state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
*
* @retval true The driver will enter CCA state.
* @retval false The driver cannot enter CCA state due to ongoing operation.
*/
bool nrf_802154_request_cca(nrf_802154_term_t term_lvl);
/**
* @brief Request entering continuous carrier state.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
*
* @retval true The driver will enter continuous carrier state.
* @retval false The driver cannot enter continuous carrier state due to ongoing operation.
*/
bool nrf_802154_request_continuous_carrier(nrf_802154_term_t term_lvl);
/**
* @brief Request the driver to free given buffer.
*
* @param[in] p_data Pointer to the buffer to free.
*/
bool nrf_802154_request_buffer_free(uint8_t * p_data);
/**
* @brief Request the driver to update channel number used by the RADIO peripheral.
*/
bool nrf_802154_request_channel_update(void);
/**
* @brief Request the driver to update CCA configuration used by the RADIO peripheral.
*/
bool nrf_802154_request_cca_cfg_update(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_802154_REQUEST_H__

View file

@ -1,114 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements requests to the driver triggered directly by the MAC layer.
*
*/
#include "nrf_802154_request.h"
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_core.h"
#include "hal/nrf_radio.h"
#define REQUEST_FUNCTION(func_core, ...) \
bool result; \
\
result = func_core(__VA_ARGS__); \
\
return result;
void nrf_802154_request_init(void)
{
// Intentionally empty
}
bool nrf_802154_request_sleep(nrf_802154_term_t term_lvl)
{
REQUEST_FUNCTION(nrf_802154_core_sleep, term_lvl)
}
bool nrf_802154_request_receive(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
nrf_802154_notification_func_t notify_function,
bool notify_abort)
{
REQUEST_FUNCTION(nrf_802154_core_receive, term_lvl, req_orig, notify_function, notify_abort)
}
bool nrf_802154_request_transmit(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
const uint8_t * p_data,
bool cca,
bool immediate,
nrf_802154_notification_func_t notify_function)
{
REQUEST_FUNCTION(nrf_802154_core_transmit,
term_lvl,
req_orig,
p_data,
cca,
immediate,
notify_function)
}
bool nrf_802154_request_energy_detection(nrf_802154_term_t term_lvl, uint32_t time_us)
{
REQUEST_FUNCTION(nrf_802154_core_energy_detection, term_lvl, time_us)
}
bool nrf_802154_request_cca(nrf_802154_term_t term_lvl)
{
REQUEST_FUNCTION(nrf_802154_core_cca, term_lvl)
}
bool nrf_802154_request_continuous_carrier(nrf_802154_term_t term_lvl)
{
REQUEST_FUNCTION(nrf_802154_core_continuous_carrier, term_lvl)
}
bool nrf_802154_request_buffer_free(uint8_t * p_data)
{
REQUEST_FUNCTION(nrf_802154_core_notify_buffer_free, p_data)
}
bool nrf_802154_request_channel_update(void)
{
REQUEST_FUNCTION(nrf_802154_core_channel_update)
}
bool nrf_802154_request_cca_cfg_update(void)
{
REQUEST_FUNCTION(nrf_802154_core_cca_cfg_update)
}

View file

@ -1,174 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements requests to the driver triggered by the MAC layer through SWI.
*
*/
#include "nrf_802154_request.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_config.h"
#include "nrf_802154_core.h"
#include "nrf_802154_critical_section.h"
#include "nrf_802154_debug.h"
#include "nrf_802154_utils.h"
#include "nrf_802154_rx_buffer.h"
#include "nrf_802154_swi.h"
#include "hal/nrf_radio.h"
#include <nrf.h>
/** Assert if SWI interrupt is disabled. */
static inline void assert_interrupt_status(void)
{
assert(nrf_is_nvic_irq_enabled(NRF_802154_SWI_IRQN));
}
#define REQUEST_FUNCTION(func_core, func_swi, ...) \
bool result = false; \
\
if (active_vector_priority_is_high()) \
{ \
result = func_core(__VA_ARGS__); \
} \
else \
{ \
assert_interrupt_status(); \
func_swi(__VA_ARGS__, &result); \
} \
\
return result;
#define REQUEST_FUNCTION_NO_ARGS(func_core, func_swi) \
bool result = false; \
\
if (active_vector_priority_is_high()) \
{ \
result = func_core(); \
} \
else \
{ \
assert_interrupt_status(); \
func_swi(&result); \
} \
\
return result;
/** Check if active vector priority is high enough to call requests directly.
*
* @retval true Active vector priority is greater or equal to SWI priority.
* @retval false Active vector priority is lower than SWI priority.
*/
static bool active_vector_priority_is_high(void)
{
return nrf_802154_critical_section_active_vector_priority_get() <= NRF_802154_SWI_PRIORITY;
}
void nrf_802154_request_init(void)
{
nrf_802154_swi_init();
}
bool nrf_802154_request_sleep(nrf_802154_term_t term_lvl)
{
REQUEST_FUNCTION(nrf_802154_core_sleep, nrf_802154_swi_sleep, term_lvl)
}
bool nrf_802154_request_receive(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
nrf_802154_notification_func_t notify_function,
bool notify_abort)
{
REQUEST_FUNCTION(nrf_802154_core_receive,
nrf_802154_swi_receive,
term_lvl,
req_orig,
notify_function,
notify_abort)
}
bool nrf_802154_request_transmit(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
const uint8_t * p_data,
bool cca,
bool immediate,
nrf_802154_notification_func_t notify_function)
{
REQUEST_FUNCTION(nrf_802154_core_transmit,
nrf_802154_swi_transmit,
term_lvl,
req_orig,
p_data,
cca,
immediate,
notify_function)
}
bool nrf_802154_request_energy_detection(nrf_802154_term_t term_lvl,
uint32_t time_us)
{
REQUEST_FUNCTION(nrf_802154_core_energy_detection,
nrf_802154_swi_energy_detection,
term_lvl,
time_us)
}
bool nrf_802154_request_cca(nrf_802154_term_t term_lvl)
{
REQUEST_FUNCTION(nrf_802154_core_cca, nrf_802154_swi_cca, term_lvl)
}
bool nrf_802154_request_continuous_carrier(nrf_802154_term_t term_lvl)
{
REQUEST_FUNCTION(nrf_802154_core_continuous_carrier, nrf_802154_swi_continuous_carrier,
term_lvl)
}
bool nrf_802154_request_buffer_free(uint8_t * p_data)
{
REQUEST_FUNCTION(nrf_802154_core_notify_buffer_free, nrf_802154_swi_buffer_free, p_data)
}
bool nrf_802154_request_channel_update(void)
{
REQUEST_FUNCTION_NO_ARGS(nrf_802154_core_channel_update, nrf_802154_swi_channel_update)
}
bool nrf_802154_request_cca_cfg_update(void)
{
REQUEST_FUNCTION_NO_ARGS(nrf_802154_core_cca_cfg_update, nrf_802154_swi_cca_cfg_update)
}

View file

@ -1,133 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements helpers for checking nRF SoC revision.
*
*/
#include "nrf_802154_revision.h"
#include <assert.h>
/** @breif Types of nRF52840 revisions. */
typedef enum
{
NRF52840_REVISION_AAAA,
NRF52840_REVISION_AABA,
NRF52840_REVISION_UNKNOWN,
} nrf_802154_chip_revision;
static nrf_802154_chip_revision m_nrf52840_revision = NRF52840_REVISION_UNKNOWN;
/**
* @brief Internal auxiliary function to check if the program is running on NRF52840 chip.
*
* @retval true If it is NRF52480 chip.
* @retval false If it is other chip.
*/
static inline bool nrf_revision_type_52840(void)
{
return ((((*(uint32_t *)0xF0000FE0) & 0xFF) == 0x08) &&
(((*(uint32_t *)0xF0000FE4) & 0x0F) == 0x00));
}
/**
* @brief Internal auxiliary function to check if the program is running
* on the AAAA revision of the nRF52840 chip.
*
* @retval true If it is NRF52480_AAAA chip revision.
* @retval false It is other chip revision.
*/
static inline bool nrf_revision_type_52840_aaaa(void)
{
return (nrf_revision_type_52840() &&
(((*(uint32_t *)0xF0000FE8) & 0xF0) == 0x00) && // revision
(((*(uint32_t *)0xF0000FEC) & 0xF0) == 0x00)); // sub-revision
}
/**
* @brief Internal auxiliary function to check if the program is running
* on the AABA revision of the nRF52840 chip.
*
* @retval true If it is NRF52480_AAAA chip revision.
* @retval false It is other chip revision.
*/
static inline bool nrf_revision_type_52840_aaba(void)
{
return (nrf_revision_type_52840() &&
(((*(uint32_t *)0xF0000FE8) & 0xF0) == 0x10) && // revision
(((*(uint32_t *)0xF0000FEC) & 0xF0) == 0x00)); // sub-revision
}
void nrf_802154_revision_init(void)
{
if (nrf_revision_type_52840_aaaa())
{
m_nrf52840_revision = NRF52840_REVISION_AAAA;
}
else if (nrf_revision_type_52840_aaba())
{
m_nrf52840_revision = NRF52840_REVISION_AABA;
}
else
{
m_nrf52840_revision = NRF52840_REVISION_UNKNOWN;
}
}
bool nrf_802154_revision_has_phyend_event(void)
{
#if NRF52840_AAAA
return false;
#elif NRF52840_AABA
return true;
#else
bool result = false;
switch (m_nrf52840_revision)
{
case NRF52840_REVISION_AAAA:
result = false;
break;
case NRF52840_REVISION_AABA:
case NRF52840_REVISION_UNKNOWN:
result = true;
break;
default:
assert(false);
}
return result;
#endif // NRF52840_AAAA
}

View file

@ -1,67 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module contains helpers for checking nRF SoC revision.
*
*/
#ifndef NRF_802154_REVISION_H_
#define NRF_802154_REVISION_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief This function initializes the module by reading the nRF52840 revision
* from the registers and storing it for convenient access.
*
* @note If the chip revision is not recognized, this module assumes that it is running on a newer
* chip revision that has all of the features, that the most recent known revision has.
*/
void nrf_802154_revision_init(void);
/**
* @brief Function to check if the program is running on NRF52840 revision that supports PHYEND event.
*
* @retval true If PHYEND event is supported.
* @retval false If PHYEND event is not supported.
*/
bool nrf_802154_revision_has_phyend_event(void);
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_REVISION_H_ */

View file

@ -1,96 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements RSSI calculations for 802.15.4 driver.
*
*/
#include <stdint.h>
#include "platform/temperature/nrf_802154_temperature.h"
int8_t nrf_802154_rssi_sample_temp_corr_value_get(void)
{
int8_t temp = nrf_802154_temperature_get();
int8_t result;
if (temp <= -30)
{
result = 3;
}
else if (temp <= -10)
{
result = 2;
}
else if (temp <= 10)
{
result = 1;
}
else if (temp <= 30)
{
result = 0;
}
else if (temp <= 50)
{
result = -1;
}
else if (temp <= 70)
{
result = -2;
}
else
{
result = -3;
}
return result;
}
uint8_t nrf_802154_rssi_sample_corrected_get(uint8_t rssi_sample)
{
return rssi_sample + nrf_802154_rssi_sample_temp_corr_value_get();
}
uint8_t nrf_802154_rssi_lqi_corrected_get(uint8_t lqi)
{
return lqi - nrf_802154_rssi_sample_temp_corr_value_get();
}
uint8_t nrf_802154_rssi_ed_corrected_get(uint8_t ed)
{
return ed - nrf_802154_rssi_sample_temp_corr_value_get();
}
uint8_t nrf_802154_rssi_cca_ed_threshold_corrected_get(uint8_t cca_ed)
{
return cca_ed - nrf_802154_rssi_sample_temp_corr_value_get();
}

View file

@ -1,90 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_RSSI_H__
#define NRF_802154_RSSI_H__
#include <stdint.h>
/**
* @defgroup nrf_802154_rssi RSSI calculations used internally in the 802.15.4 driver.
* @{
* @ingroup nrf_802154
* @brief RSSI calculations used internally in the 802.15.4 driver.
*/
/**
* @brief Get RSSISAMPLE temperature correction value for temperature provided by platform.
*
* @returns RSSISAMPLE temperature correction value (Errata 153).
*/
int8_t nrf_802154_rssi_sample_temp_corr_value_get(void);
/**
* @brief Adjust the given RSSISAMPLE value using a temperature correction factor.
*
* @param[in] rssi_sample Value read from RSSISAMPLE register.
*
* @returns RSSISAMPLE corrected by a temperature factor (Errata 153).
*/
uint8_t nrf_802154_rssi_sample_corrected_get(uint8_t rssi_sample);
/**
* @brief Adjust the reported LQI value using a temperature correction factor.
*
* @param[in] lqi Value read from LQI byte.
*
* @returns LQI byte value corrected by a temperature factor (Errata 153).
*/
uint8_t nrf_802154_rssi_lqi_corrected_get(uint8_t lqi);
/**
* @brief Adjust the EDSAMPLE value using a temperature correction factor.
*
* @param[in] ed Value read from EDSAMPLE register.
*
* @returns EDSAMPLE value corrected by a temperature factor (Errata 153).
*/
uint8_t nrf_802154_rssi_ed_corrected_get(uint8_t ed);
/**
* @brief Adjust the CCA ED threshold value using a temperature correction factor.
*
* @param[in] cca_ed Value representing CCA ED threshold that should be corrected.
*
* @returns CCA ED threshold value corrected by a temperature factor (Errata 153).
*/
uint8_t nrf_802154_rssi_cca_ed_threshold_corrected_get(uint8_t cca_ed);
/**
*@}
**/
#endif // NRF_802154_RSSI_H__

View file

@ -1,68 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements buffer management for frames received by nRF 802.15.4 radio driver.
*
*/
#include "nrf_802154_rx_buffer.h"
#include <stddef.h>
#include "nrf_802154_config.h"
#if NRF_802154_RX_BUFFERS < 1
#error Not enough rx buffers in the 802.15.4 radio driver.
#endif
rx_buffer_t nrf_802154_rx_buffers[NRF_802154_RX_BUFFERS]; ///< Receive buffers.
void nrf_802154_rx_buffer_init(void)
{
for (uint32_t i = 0; i < NRF_802154_RX_BUFFERS; i++)
{
nrf_802154_rx_buffers[i].free = true;
}
}
rx_buffer_t * nrf_802154_rx_buffer_free_find(void)
{
for (uint32_t i = 0; i < NRF_802154_RX_BUFFERS; i++)
{
if (nrf_802154_rx_buffers[i].free)
{
return &nrf_802154_rx_buffers[i];
}
}
return NULL;
}

View file

@ -1,82 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module contains buffer for frames received by nRF 802.15.4 radio driver.
*
*/
#ifndef NRF_802154_RX_BUFFER_H_
#define NRF_802154_RX_BUFFER_H_
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_const.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Structure containing received frame.
*/
typedef struct
{
uint8_t psdu[MAX_PACKET_SIZE + 1];
bool free; // If this buffer is free or contains a frame.
} rx_buffer_t;
/**
* @brief Array containing all buffers used to receive frame.
*
* This array is in global scope to allow optimizations in Core module in case there is only
* one buffer provided by this module.
*
*/
extern rx_buffer_t nrf_802154_rx_buffers[];
/**
* @brief Initialize buffer for received frames.
*/
void nrf_802154_rx_buffer_init(void);
/**
* @brief Get free buffer to receive a frame.
*
* @return Pointer to free buffer of NULL if no free buffer is available.
*/
rx_buffer_t * nrf_802154_rx_buffer_free_find(void);
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_RX_BUFFER_H_ */

View file

@ -1,819 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements SWI manager for nRF 802.15.4 driver.
*
*/
#include "nrf_802154_swi.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154.h"
#include "nrf_802154_config.h"
#include "nrf_802154_core.h"
#include "nrf_802154_rx_buffer.h"
#include "hal/nrf_egu.h"
#include "platform/clock/nrf_802154_clock.h"
/** Size of notification queue.
*
* One slot for each receive buffer, one for transmission, one for busy channel and one for energy
* detection.
*/
#define NTF_QUEUE_SIZE (NRF_802154_RX_BUFFERS + 3)
/** Size of requests queue.
*
* Two is minimal queue size. It is not expected in current implementation to queue a few requests.
*/
#define REQ_QUEUE_SIZE 2
#define SWI_EGU NRF_802154_SWI_EGU_INSTANCE ///< Label of SWI peripheral.
#define SWI_IRQn NRF_802154_SWI_IRQN ///< Symbol of SWI IRQ number.
#define SWI_IRQHandler NRF_802154_SWI_IRQ_HANDLER ///< Symbol of SWI IRQ handler.
#define NTF_INT NRF_EGU_INT_TRIGGERED0 ///< Label of notification interrupt.
#define NTF_TASK NRF_EGU_TASK_TRIGGER0 ///< Label of notification task.
#define NTF_EVENT NRF_EGU_EVENT_TRIGGERED0 ///< Label of notification event.
#define HFCLK_STOP_INT NRF_EGU_INT_TRIGGERED1 ///< Label of HFClk stop interrupt.
#define HFCLK_STOP_TASK NRF_EGU_TASK_TRIGGER1 ///< Label of HFClk stop task.
#define HFCLK_STOP_EVENT NRF_EGU_EVENT_TRIGGERED1 ///< Label of HFClk stop event.
#define REQ_INT NRF_EGU_INT_TRIGGERED2 ///< Label of request interrupt.
#define REQ_TASK NRF_EGU_TASK_TRIGGER2 ///< Label of request task.
#define REQ_EVENT NRF_EGU_EVENT_TRIGGERED2 ///< Label of request event.
#define RAW_LENGTH_OFFSET 0
#define RAW_PAYLOAD_OFFSET 1
/// Types of notifications in notification queue.
typedef enum
{
NTF_TYPE_RECEIVED, ///< Frame received
NTF_TYPE_RECEIVE_FAILED, ///< Frame reception failed
NTF_TYPE_TRANSMITTED, ///< Frame transmitted
NTF_TYPE_TRANSMIT_FAILED, ///< Frame transmission failure
NTF_TYPE_ENERGY_DETECTED, ///< Energy detection procedure ended
NTF_TYPE_ENERGY_DETECTION_FAILED, ///< Energy detection procedure failed
NTF_TYPE_CCA, ///< CCA procedure ended
NTF_TYPE_CCA_FAILED, ///< CCA procedure failed
} nrf_802154_ntf_type_t;
/// Notification data in the notification queue.
typedef struct
{
nrf_802154_ntf_type_t type; ///< Notification type.
union
{
struct
{
uint8_t * p_psdu; ///< Pointer to received frame PSDU.
int8_t power; ///< RSSI of received frame.
int8_t lqi; ///< LQI of received frame.
} received; ///< Received frame details.
struct
{
nrf_802154_rx_error_t error; ///< An error code that indicates reason of the failure.
} receive_failed;
struct
{
const uint8_t * p_frame; ///< Pointer to frame that was transmitted.
uint8_t * p_psdu; ///< Pointer to received ACK PSDU or NULL.
int8_t power; ///< RSSI of received ACK or 0.
int8_t lqi; ///< LQI of received ACK or 0.
} transmitted; ///< Transmitted frame details.
struct
{
const uint8_t * p_frame; ///< Pointer to frame that was requested to be transmitted, but failed.
nrf_802154_tx_error_t error; ///< An error code that indicates reason of the failure.
} transmit_failed;
struct
{
int8_t result; ///< Energy detection result.
} energy_detected; ///< Energy detection details.
struct
{
nrf_802154_ed_error_t error; ///< An error code that indicates reason of the failure.
} energy_detection_failed; ///< Energy detection failure details.
struct
{
bool result; ///< CCA result.
} cca; ///< CCA details.
struct
{
nrf_802154_cca_error_t error; ///< An error code that indicates reason of the failure.
} cca_failed; ///< CCA failure details.
} data; ///< Notification data depending on it's type.
} nrf_802154_ntf_data_t;
/// Type of requests in request queue.
typedef enum
{
REQ_TYPE_SLEEP,
REQ_TYPE_RECEIVE,
REQ_TYPE_TRANSMIT,
REQ_TYPE_ENERGY_DETECTION,
REQ_TYPE_CCA,
REQ_TYPE_CONTINUOUS_CARRIER,
REQ_TYPE_BUFFER_FREE,
REQ_TYPE_CHANNEL_UPDATE,
REQ_TYPE_CCA_CFG_UPDATE
} nrf_802154_req_type_t;
/// Request data in request queue.
typedef struct
{
nrf_802154_req_type_t type; ///< Type of the request.
union
{
struct
{
nrf_802154_term_t term_lvl; ///< Request priority.
bool * p_result; ///< Sleep request result.
} sleep; ///< Sleep request details.
struct
{
nrf_802154_notification_func_t notif_func; ///< Error notified in case of success.
nrf_802154_term_t term_lvl; ///< Request priority.
req_originator_t req_orig; ///< Request originator.
bool notif_abort; ///< If function termination should be notified.
bool * p_result; ///< Receive request result.
} receive; ///< Receive request details.
struct
{
nrf_802154_notification_func_t notif_func; ///< Error notified in case of success.
nrf_802154_term_t term_lvl; ///< Request priority.
req_originator_t req_orig; ///< Request originator.
const uint8_t * p_data; ///< Pointer to PSDU to transmit.
bool cca; ///< If CCA was requested prior to transmission.
bool immediate; ///< If TX procedure must be performed immediately.
bool * p_result; ///< Transmit request result.
} transmit; ///< Transmit request details.
struct
{
nrf_802154_term_t term_lvl; ///< Request priority.
bool * p_result; ///< Energy detection request result.
uint32_t time_us; ///< Requested time of energy detection procedure.
} energy_detection; ///< Energy detection request details.
struct
{
nrf_802154_term_t term_lvl; ///< Request priority.
bool * p_result; ///< CCA request result.
} cca; ///< CCA request details.
struct
{
nrf_802154_term_t term_lvl; ///< Request priority.
bool * p_result; ///< Continuous carrier request result.
} continuous_carrier; ///< Continuous carrier request details.
struct
{
uint8_t * p_data; ///< Pointer to receive buffer to free.
bool * p_result; ///< Buffer free request result.
} buffer_free; ///< Buffer free request details.
struct
{
bool * p_result; ///< Channel update request result.
} channel_update; ///< Channel update request details.
struct
{
bool * p_result; ///< CCA config update request result.
} cca_cfg_update; ///< CCA config update request details.
} data; ///< Request data depending on it's type.
} nrf_802154_req_data_t;
static nrf_802154_ntf_data_t m_ntf_queue[NTF_QUEUE_SIZE]; ///< Notification queue.
static uint8_t m_ntf_r_ptr; ///< Notification queue read index.
static uint8_t m_ntf_w_ptr; ///< Notification queue write index.
static nrf_802154_req_data_t m_req_queue[REQ_QUEUE_SIZE]; ///< Request queue.
static uint8_t m_req_r_ptr; ///< Request queue read index.
static uint8_t m_req_w_ptr; ///< Request queue write index.
/**
* Increment given index for any queue.
*
* @param[inout] p_ptr Index to increment.
* @param[in] queue_size Number of elements in the queue.
*/
static void queue_ptr_increment(uint8_t * p_ptr, uint8_t queue_size)
{
if (++(*p_ptr) >= queue_size)
{
*p_ptr = 0;
}
}
/**
* Check if given queue is full.
*
* @param[in] r_ptr Read index associated with given queue.
* @param[in] w_ptr Write index associated with given queue.
* @param[in] queue_size Number of elements in the queue.
*
* @retval true Given queue is full.
* @retval false Given queue is not full.
*/
static bool queue_is_full(uint8_t r_ptr, uint8_t w_ptr, uint8_t queue_size)
{
if (w_ptr == (r_ptr - 1))
{
return true;
}
if ((r_ptr == 0) && (w_ptr == queue_size - 1))
{
return true;
}
return false;
}
/**
* Check if given queue is empty.
*
* @param[in] r_ptr Read index associated with given queue.
* @param[in] w_ptr Write index associated with given queue.
*
* @retval true Given queue is empty.
* @retval false Given queue is not empty.
*/
static bool queue_is_empty(uint8_t r_ptr, uint8_t w_ptr)
{
return (r_ptr == w_ptr);
}
/**
* Increment given index associated with notification queue.
*
* @param[inout] p_ptr Pointer to the index to increment.
*/
static void ntf_queue_ptr_increment(uint8_t * p_ptr)
{
queue_ptr_increment(p_ptr, NTF_QUEUE_SIZE);
}
/**
* Check if notification queue is full.
*
* @retval true Notification queue is full.
* @retval false Notification queue is not full.
*/
static bool ntf_queue_is_full(void)
{
return queue_is_full(m_ntf_r_ptr, m_ntf_w_ptr, NTF_QUEUE_SIZE);
}
/**
* Check if notification queue is empty.
*
* @retval true Notification queue is empty.
* @retval false Notification queue is not empty.
*/
static bool ntf_queue_is_empty(void)
{
return queue_is_empty(m_ntf_r_ptr, m_ntf_w_ptr);
}
/**
* Enter notify block.
*
* This is a helper function used in all notification functions to atomically
* find an empty slot in the notification queue and allow atomic slot update.
*
* @return Pointer to an empty slot in the notification queue.
*/
static nrf_802154_ntf_data_t * ntf_enter(void)
{
__disable_irq();
__DSB();
__ISB();
assert(!ntf_queue_is_full());
(void)ntf_queue_is_full();
return &m_ntf_queue[m_ntf_w_ptr];
}
/**
* Exit notify block.
*
* This is a helper function used in all notification functions to end atomic slot update
* and trigger SWI to process the notification from the slot.
*/
static void ntf_exit(void)
{
ntf_queue_ptr_increment(&m_ntf_w_ptr);
nrf_egu_task_trigger(SWI_EGU, NTF_TASK);
__enable_irq();
}
/**
* Increment given index associated with request queue.
*
* @param[inout] p_ptr Pointer to the index to increment.
*/
static void req_queue_ptr_increment(uint8_t * p_ptr)
{
queue_ptr_increment(p_ptr, REQ_QUEUE_SIZE);
}
/**
* Check if request queue is full.
*
* @retval true Request queue is full.
* @retval false Request queue is not full.
*/
static bool req_queue_is_full(void)
{
return queue_is_full(m_req_r_ptr, m_req_w_ptr, REQ_QUEUE_SIZE);
}
/**
* Check if request queue is empty.
*
* @retval true Request queue is empty.
* @retval false Request queue is not empty.
*/
static bool req_queue_is_empty(void)
{
return queue_is_empty(m_req_r_ptr, m_req_w_ptr);
}
/**
* Enter request block.
*
* This is a helper function used in all request functions to atomically
* find an empty slot in request queue and allow atomic slot update.
*
* @return Pointer to an empty slot in the request queue.
*/
static nrf_802154_req_data_t * req_enter(void)
{
__disable_irq();
__DSB();
__ISB();
assert(!req_queue_is_full());
(void)req_queue_is_full();
return &m_req_queue[m_req_w_ptr];
}
/**
* Exit request block.
*
* This is a helper function used in all request functions to end atomic slot update
* and trigger SWI to process the request from the slot.
*/
static void req_exit(void)
{
req_queue_ptr_increment(&m_req_w_ptr);
nrf_egu_task_trigger(SWI_EGU, REQ_TASK);
__enable_irq();
__DSB();
__ISB();
}
void nrf_802154_swi_init(void)
{
m_ntf_r_ptr = 0;
m_ntf_w_ptr = 0;
nrf_egu_int_enable(SWI_EGU, NTF_INT | HFCLK_STOP_INT | REQ_INT);
NVIC_SetPriority(SWI_IRQn, NRF_802154_SWI_PRIORITY);
NVIC_ClearPendingIRQ(SWI_IRQn);
NVIC_EnableIRQ(SWI_IRQn);
}
void nrf_802154_swi_notify_received(uint8_t * p_data, int8_t power, int8_t lqi)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_RECEIVED;
p_slot->data.received.p_psdu = p_data;
p_slot->data.received.power = power;
p_slot->data.received.lqi = lqi;
ntf_exit();
}
void nrf_802154_swi_notify_receive_failed(nrf_802154_rx_error_t error)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_RECEIVE_FAILED;
p_slot->data.receive_failed.error = error;
ntf_exit();
}
void nrf_802154_swi_notify_transmitted(const uint8_t * p_frame,
uint8_t * p_data,
int8_t power,
int8_t lqi)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_TRANSMITTED;
p_slot->data.transmitted.p_frame = p_frame;
p_slot->data.transmitted.p_psdu = p_data;
p_slot->data.transmitted.power = power;
p_slot->data.transmitted.lqi = lqi;
ntf_exit();
}
void nrf_802154_swi_notify_transmit_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_TRANSMIT_FAILED;
p_slot->data.transmit_failed.p_frame = p_frame;
p_slot->data.transmit_failed.error = error;
ntf_exit();
}
void nrf_802154_swi_notify_energy_detected(uint8_t result)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_ENERGY_DETECTED;
p_slot->data.energy_detected.result = result;
ntf_exit();
}
void nrf_802154_swi_notify_energy_detection_failed(nrf_802154_ed_error_t error)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_ENERGY_DETECTION_FAILED;
p_slot->data.energy_detection_failed.error = error;
ntf_exit();
}
void nrf_802154_swi_notify_cca(bool channel_free)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_CCA;
p_slot->data.cca.result = channel_free;
ntf_exit();
}
void nrf_802154_swi_notify_cca_failed(nrf_802154_cca_error_t error)
{
nrf_802154_ntf_data_t * p_slot = ntf_enter();
p_slot->type = NTF_TYPE_CCA_FAILED;
p_slot->data.cca_failed.error = error;
ntf_exit();
}
void nrf_802154_swi_hfclk_stop(void)
{
assert(!nrf_egu_event_check(SWI_EGU, HFCLK_STOP_EVENT));
nrf_egu_task_trigger(SWI_EGU, HFCLK_STOP_TASK);
}
void nrf_802154_swi_hfclk_stop_terminate(void)
{
nrf_egu_event_clear(SWI_EGU, HFCLK_STOP_EVENT);
}
void nrf_802154_swi_sleep(nrf_802154_term_t term_lvl, bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_SLEEP;
p_slot->data.sleep.term_lvl = term_lvl;
p_slot->data.sleep.p_result = p_result;
req_exit();
}
void nrf_802154_swi_receive(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
nrf_802154_notification_func_t notify_function,
bool notify_abort,
bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_RECEIVE;
p_slot->data.receive.term_lvl = term_lvl;
p_slot->data.receive.req_orig = req_orig;
p_slot->data.receive.notif_func = notify_function;
p_slot->data.receive.notif_abort = notify_abort;
p_slot->data.receive.p_result = p_result;
req_exit();
}
void nrf_802154_swi_transmit(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
const uint8_t * p_data,
bool cca,
bool immediate,
nrf_802154_notification_func_t notify_function,
bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_TRANSMIT;
p_slot->data.transmit.term_lvl = term_lvl;
p_slot->data.transmit.req_orig = req_orig;
p_slot->data.transmit.p_data = p_data;
p_slot->data.transmit.cca = cca;
p_slot->data.transmit.immediate = immediate;
p_slot->data.transmit.notif_func = notify_function;
p_slot->data.transmit.p_result = p_result;
req_exit();
}
void nrf_802154_swi_energy_detection(nrf_802154_term_t term_lvl,
uint32_t time_us,
bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_ENERGY_DETECTION;
p_slot->data.energy_detection.term_lvl = term_lvl;
p_slot->data.energy_detection.time_us = time_us;
p_slot->data.energy_detection.p_result = p_result;
req_exit();
}
void nrf_802154_swi_cca(nrf_802154_term_t term_lvl, bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_CCA;
p_slot->data.cca.term_lvl = term_lvl;
p_slot->data.cca.p_result = p_result;
req_exit();
}
void nrf_802154_swi_continuous_carrier(nrf_802154_term_t term_lvl, bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_CONTINUOUS_CARRIER;
p_slot->data.continuous_carrier.term_lvl = term_lvl;
p_slot->data.continuous_carrier.p_result = p_result;
req_exit();
}
void nrf_802154_swi_buffer_free(uint8_t * p_data, bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_BUFFER_FREE;
p_slot->data.buffer_free.p_data = p_data;
p_slot->data.buffer_free.p_result = p_result;
req_exit();
}
void nrf_802154_swi_channel_update(bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_CHANNEL_UPDATE;
p_slot->data.channel_update.p_result = p_result;
req_exit();
}
void nrf_802154_swi_cca_cfg_update(bool * p_result)
{
nrf_802154_req_data_t * p_slot = req_enter();
p_slot->type = REQ_TYPE_CCA_CFG_UPDATE;
p_slot->data.cca_cfg_update.p_result = p_result;
req_exit();
}
void SWI_IRQHandler(void)
{
if (nrf_egu_event_check(SWI_EGU, NTF_EVENT))
{
nrf_egu_event_clear(SWI_EGU, NTF_EVENT);
while (!ntf_queue_is_empty())
{
nrf_802154_ntf_data_t * p_slot = &m_ntf_queue[m_ntf_r_ptr];
switch (p_slot->type)
{
case NTF_TYPE_RECEIVED:
#if NRF_802154_USE_RAW_API
nrf_802154_received_raw(p_slot->data.received.p_psdu,
p_slot->data.received.power,
p_slot->data.received.lqi);
#else // NRF_802154_USE_RAW_API
nrf_802154_received(p_slot->data.received.p_psdu + RAW_PAYLOAD_OFFSET,
p_slot->data.received.p_psdu[RAW_LENGTH_OFFSET],
p_slot->data.received.power,
p_slot->data.received.lqi);
#endif
break;
case NTF_TYPE_RECEIVE_FAILED:
nrf_802154_receive_failed(p_slot->data.receive_failed.error);
break;
case NTF_TYPE_TRANSMITTED:
#if NRF_802154_USE_RAW_API
nrf_802154_transmitted_raw(p_slot->data.transmitted.p_frame,
p_slot->data.transmitted.p_psdu,
p_slot->data.transmitted.power,
p_slot->data.transmitted.lqi);
#else // NRF_802154_USE_RAW_API
nrf_802154_transmitted(p_slot->data.transmitted.p_frame + RAW_PAYLOAD_OFFSET,
p_slot->data.transmitted.p_psdu == NULL ? NULL :
p_slot->data.transmitted.p_psdu + RAW_PAYLOAD_OFFSET,
p_slot->data.transmitted.p_psdu[RAW_LENGTH_OFFSET],
p_slot->data.transmitted.power,
p_slot->data.transmitted.lqi);
#endif
break;
case NTF_TYPE_TRANSMIT_FAILED:
#if NRF_802154_USE_RAW_API
nrf_802154_transmit_failed(p_slot->data.transmit_failed.p_frame,
p_slot->data.transmit_failed.error);
#else // NRF_802154_USE_RAW_API
nrf_802154_transmit_failed(
p_slot->data.transmit_failed.p_frame + RAW_PAYLOAD_OFFSET,
p_slot->data.transmit_failed.error);
#endif
break;
case NTF_TYPE_ENERGY_DETECTED:
nrf_802154_energy_detected(p_slot->data.energy_detected.result);
break;
case NTF_TYPE_ENERGY_DETECTION_FAILED:
nrf_802154_energy_detection_failed(
p_slot->data.energy_detection_failed.error);
break;
case NTF_TYPE_CCA:
nrf_802154_cca_done(p_slot->data.cca.result);
break;
case NTF_TYPE_CCA_FAILED:
nrf_802154_cca_failed(p_slot->data.cca_failed.error);
break;
default:
assert(false);
}
ntf_queue_ptr_increment(&m_ntf_r_ptr);
}
}
if (nrf_egu_event_check(SWI_EGU, HFCLK_STOP_EVENT))
{
nrf_802154_clock_hfclk_stop();
nrf_egu_event_clear(SWI_EGU, HFCLK_STOP_EVENT);
}
if (nrf_egu_event_check(SWI_EGU, REQ_EVENT))
{
nrf_egu_event_clear(SWI_EGU, REQ_EVENT);
while (!req_queue_is_empty())
{
nrf_802154_req_data_t * p_slot = &m_req_queue[m_req_r_ptr];
switch (p_slot->type)
{
case REQ_TYPE_SLEEP:
*(p_slot->data.sleep.p_result) =
nrf_802154_core_sleep(p_slot->data.sleep.term_lvl);
break;
case REQ_TYPE_RECEIVE:
*(p_slot->data.receive.p_result) =
nrf_802154_core_receive(p_slot->data.receive.term_lvl,
p_slot->data.receive.req_orig,
p_slot->data.receive.notif_func,
p_slot->data.receive.notif_abort);
break;
case REQ_TYPE_TRANSMIT:
*(p_slot->data.transmit.p_result) =
nrf_802154_core_transmit(p_slot->data.transmit.term_lvl,
p_slot->data.transmit.req_orig,
p_slot->data.transmit.p_data,
p_slot->data.transmit.cca,
p_slot->data.transmit.immediate,
p_slot->data.transmit.notif_func);
break;
case REQ_TYPE_ENERGY_DETECTION:
*(p_slot->data.energy_detection.p_result) =
nrf_802154_core_energy_detection(
p_slot->data.energy_detection.term_lvl,
p_slot->data.energy_detection.time_us);
break;
case REQ_TYPE_CCA:
*(p_slot->data.cca.p_result) = nrf_802154_core_cca(p_slot->data.cca.term_lvl);
break;
case REQ_TYPE_CONTINUOUS_CARRIER:
*(p_slot->data.continuous_carrier.p_result) =
nrf_802154_core_continuous_carrier(
p_slot->data.continuous_carrier.term_lvl);
break;
case REQ_TYPE_BUFFER_FREE:
*(p_slot->data.buffer_free.p_result) =
nrf_802154_core_notify_buffer_free(p_slot->data.buffer_free.p_data);
break;
case REQ_TYPE_CHANNEL_UPDATE:
*(p_slot->data.channel_update.p_result) = nrf_802154_core_channel_update();
break;
case REQ_TYPE_CCA_CFG_UPDATE:
*(p_slot->data.cca_cfg_update.p_result) = nrf_802154_core_cca_cfg_update();
break;
default:
assert(false);
}
req_queue_ptr_increment(&m_req_r_ptr);
}
}
}

View file

@ -1,235 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_SWI_H__
#define NRF_802154_SWI_H__
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154.h"
#include "nrf_802154_const.h"
#include "nrf_802154_notification.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_swi 802.15.4 driver SWI management
* @{
* @ingroup nrf_802154
* @brief SWI manager for 802.15.4 driver.
*/
/**
* @brief Initialize SWI module.
*/
void nrf_802154_swi_init(void);
/**
* @brief Notify next higher layer that a frame was received from SWI priority level.
*
* @param[in] p_data Array of bytes containing PSDU. First byte contains frame length, other contain the frame itself.
* @param[in] power RSSI measured during the frame reception.
* @param[in] lqi LQI indicating measured link quality during the frame reception.
*/
void nrf_802154_swi_notify_received(uint8_t * p_data, int8_t power, int8_t lqi);
/**
* @brief Notify next higher layer that reception of a frame failed.
*
* @param[in] error An error code that indicates reason of the failure.
*/
void nrf_802154_swi_notify_receive_failed(nrf_802154_rx_error_t error);
/**
* @brief Notify next higher layer that a frame was transmitted from SWI priority level.
*
* @param[in] p_frame Pointer to buffer containing PSDU of transmitted frame.
* @param[in] p_ack Pointer to buffer containing PSDU of ACK frame. NULL if ACK was not requested.
* @param[in] power RSSI of received frame or 0 if ACK was not requested.
* @param[in] lqi LQI of received frame of 0 if ACK was not requested.
*/
void nrf_802154_swi_notify_transmitted(const uint8_t * p_frame,
uint8_t * p_data,
int8_t power,
int8_t lqi);
/**
* @brief Notify next higher layer that a frame was not transmitted from SWI priority level.
*
* @param[in] p_frame Pointer to buffer containing PSDU of the frame that failed transmit
* operation.
* @param[in] error Reason of the transmission failure.
*/
void nrf_802154_swi_notify_transmit_failed(const uint8_t * p_frame, nrf_802154_tx_error_t error);
/**
* @brief Notify next higher layer that energy detection procedure ended from SWI priority level.
*
* @param[in] result Detected energy level.
*/
void nrf_802154_swi_notify_energy_detected(uint8_t result);
/**
* @brief Notify next higher layer that energy detection procedure failed from SWI priority level.
*
* @param[in] error Reason of the energy detection failure.
*/
void nrf_802154_swi_notify_energy_detection_failed(nrf_802154_ed_error_t error);
/**
* @brief Notify next higher layer that CCA procedure ended from SWI priority level.
*
* @param[in] channel_free If detected free channel.
*/
void nrf_802154_swi_notify_cca(bool channel_free);
/**
* @brief Notify next higher layer that CCA procedure failed from SWI priority level.
*
* @param[in] error Reason of the CCA failure.
*/
void nrf_802154_swi_notify_cca_failed(nrf_802154_cca_error_t error);
/**
* @brief Request stop of the HF clock from the SWI priority level.
*
* @note This function should be called through notification module to prevent calling it from
* the arbiter context.
*/
void nrf_802154_swi_hfclk_stop(void);
/**
* @brief Terminate stopping of the HF clock.
*
* @note This function terminates stopping of the HF clock only if it has not been performed.
*/
void nrf_802154_swi_hfclk_stop_terminate(void);
/**
* @brief Request entering sleep state from SWI priority.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[out] p_result Result of entering sleep state.
*/
void nrf_802154_swi_sleep(nrf_802154_term_t term_lvl, bool * p_result);
/**
* @brief Request entering receive state from SWI priority.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @param[in] notify_function Function called to notify status of this procedure. May be NULL.
* @param[in] notify_abort If abort notification should be triggered automatically.
* @param[out] p_result Result of entering receive state.
*/
void nrf_802154_swi_receive(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
nrf_802154_notification_func_t notify_function,
bool notify_abort,
bool * p_result);
/**
* @biref Request entering transmit state from SWI priority.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] req_orig Module that originates this request.
* @param[in] p_data Pointer to PSDU of the frame to transmit.
* @param[in] cca If the driver should perform CCA procedure before transmission.
* @param[in] immediate If true, the driver schedules transmission immediately or never;
* if false transmission may be postponed until tx preconditions are
* met.
* @param[in] notify_function Function called to notify status of this procedure instead of
* default notification. If NULL default notification is used.
* @param[out] p_result Result of entering transmit state.
*/
void nrf_802154_swi_transmit(nrf_802154_term_t term_lvl,
req_originator_t req_orig,
const uint8_t * p_data,
bool cca,
bool immediate,
nrf_802154_notification_func_t notify_function,
bool * p_result);
/**
* @brief Request entering energy detection state from SWI priority.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[in] time_us Requested duration of energy detection procedure.
* @param[out] p_result Result of entering energy detection state.
*/
void nrf_802154_swi_energy_detection(nrf_802154_term_t term_lvl,
uint32_t time_us,
bool * p_result);
/**
* @brief Request entering CCA state from SWI priority.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[out] p_result Result of entering CCA state.
*/
void nrf_802154_swi_cca(nrf_802154_term_t term_lvl, bool * p_result);
/**
* @brief Request entering continuous carrier state from SWI priority.
*
* @param[in] term_lvl Termination level of this request. Selects procedures to abort.
* @param[out] p_result Result of entering continuous carrier state.
*/
void nrf_802154_swi_continuous_carrier(nrf_802154_term_t term_lvl, bool * p_result);
/**
* @brief Notify Core module that given buffer is not used anymore and can be freed.
*
* @param[in] p_data Pointer to the buffer to free.
*/
void nrf_802154_swi_buffer_free(uint8_t * p_data, bool * p_result);
/**
* @brief Notify Core module that the next higher layer requested channel change.
*/
void nrf_802154_swi_channel_update(bool * p_result);
/**
* @brief Notify Core module that the next higher layer requested CCA configuration change.
*/
void nrf_802154_swi_cca_cfg_update(bool * p_result);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_802154_SWI_H__

View file

@ -1,252 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements Timer Coordinator module.
*
*/
#include "nrf_802154_timer_coord.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_config.h"
#include "hal/nrf_ppi.h"
#include "platform/hp_timer/nrf_802154_hp_timer.h"
#include "platform/lp_timer/nrf_802154_lp_timer.h"
#define DIV_ROUND_POSITIVE(n, d) (((n) + (d) / 2) / (d))
#define DIV_ROUND_NEGATIVE(n, d) (((n) - (d) / 2) / (d))
#define DIV_ROUND(n, d) ((((n) < 0) ^ ((d) < 0)) ? \
DIV_ROUND_NEGATIVE(n, d) : \
DIV_ROUND_POSITIVE(n, d))
#define TIME_BASE (1UL << 22) ///< Unit used to calculate PPTB (Point per Time Base). It is not equal million to speed up computations and increase precision.
#define FIRST_RESYNC_TIME TIME_BASE ///< Delay of the first resynchronization. The first resynchronization is needed to measure timers drift.
#define RESYNC_TIME (64 * TIME_BASE) ///< Delay of following resynchronizations.
#define EWMA_COEF (8) ///< Weight used in the EWMA algorithm.
#define PPI_CH0 NRF_PPI_CHANNEL13
#define PPI_CH1 NRF_PPI_CHANNEL14
#define PPI_CHGRP0 NRF_PPI_CHANNEL_GROUP1
#define PPI_SYNC PPI_CH0
#define PPI_TIMESTAMP PPI_CH1
#define PPI_TIMESTAMP_GROUP PPI_CHGRP0
#if NRF_802154_FRAME_TIMESTAMP_ENABLED
// Structure holding common timepoint from both timers.
typedef struct
{
uint32_t lp_timer_time; ///< LP Timer time of common timepoint.
uint32_t hp_timer_time; ///< HP Timer time of common timepoint.
} common_timepoint_t;
// Static variables.
static common_timepoint_t m_last_sync; ///< Common timepoint of last synchronization event.
static volatile bool m_synchronized; ///< If timers were synchronized since last start.
static bool m_drift_known; ///< If timer drift value is known.
static int32_t m_drift; ///< Drift of the HP timer relatively to the LP timer [PPTB].
void nrf_802154_timer_coord_init(void)
{
uint32_t sync_event;
uint32_t sync_task;
m_drift = 0;
m_drift_known = 0;
nrf_802154_hp_timer_init();
sync_event = nrf_802154_lp_timer_sync_event_get();
sync_task = nrf_802154_hp_timer_sync_task_get();
nrf_ppi_channel_endpoint_setup(PPI_SYNC, sync_event, sync_task);
nrf_ppi_channel_enable(PPI_SYNC);
nrf_ppi_channel_include_in_group(PPI_TIMESTAMP, PPI_TIMESTAMP_GROUP);
}
void nrf_802154_timer_coord_uninit(void)
{
nrf_802154_hp_timer_deinit();
nrf_ppi_channel_disable(PPI_SYNC);
nrf_ppi_channel_endpoint_setup(PPI_SYNC, 0, 0);
nrf_ppi_group_disable(PPI_TIMESTAMP_GROUP);
nrf_ppi_channel_and_fork_endpoint_setup(PPI_TIMESTAMP, 0, 0, 0);
}
void nrf_802154_timer_coord_start(void)
{
m_synchronized = false;
nrf_802154_hp_timer_start();
nrf_802154_hp_timer_sync_prepare();
nrf_802154_lp_timer_sync_start_now();
}
void nrf_802154_timer_coord_stop(void)
{
nrf_802154_hp_timer_stop();
nrf_802154_lp_timer_sync_stop();
}
void nrf_802154_timer_coord_timestamp_prepare(uint32_t event_addr)
{
nrf_ppi_channel_and_fork_endpoint_setup(PPI_TIMESTAMP,
event_addr,
nrf_802154_hp_timer_timestamp_task_get(),
(uint32_t)nrf_ppi_task_group_disable_address_get(
PPI_TIMESTAMP_GROUP));
nrf_ppi_group_enable(PPI_TIMESTAMP_GROUP);
}
bool nrf_802154_timer_coord_timestamp_get(uint32_t * p_timestamp)
{
uint32_t hp_timestamp;
uint32_t hp_delta;
int32_t drift;
assert(p_timestamp != NULL);
if (!m_synchronized)
{
return false;
}
hp_timestamp = nrf_802154_hp_timer_timestamp_get();
hp_delta = hp_timestamp - m_last_sync.hp_timer_time;
drift = m_drift_known ?
(DIV_ROUND(((int64_t)m_drift * hp_delta), ((int64_t)TIME_BASE + m_drift))) : 0;
*p_timestamp = m_last_sync.lp_timer_time + hp_delta - drift;
return true;
}
void nrf_802154_lp_timer_synchronized(void)
{
common_timepoint_t sync_time;
uint32_t lp_delta;
uint32_t hp_delta;
int32_t timers_diff;
int32_t drift;
int32_t tb_fraction_of_lp_delta;
if (nrf_802154_hp_timer_sync_time_get(&sync_time.hp_timer_time))
{
sync_time.lp_timer_time = nrf_802154_lp_timer_sync_time_get();
// Calculate timers drift
if (m_synchronized)
{
lp_delta = sync_time.lp_timer_time - m_last_sync.lp_timer_time;
hp_delta = sync_time.hp_timer_time - m_last_sync.hp_timer_time;
tb_fraction_of_lp_delta = DIV_ROUND_POSITIVE(lp_delta, TIME_BASE);
timers_diff = hp_delta - lp_delta;
drift = DIV_ROUND(timers_diff, tb_fraction_of_lp_delta); // Drift in PPTB
if (m_drift_known)
{
m_drift = DIV_ROUND((m_drift * (EWMA_COEF - 1) + drift), EWMA_COEF);
}
else
{
m_drift = drift;
}
m_drift_known = true;
}
/* To avoid possible race when nrf_802154_timer_coord_timestamp_get
* is called when m_last_sync is being assigned report that we are not synchronized
* during assignment.
* This is naive solution that can be improved if needed with double buffering.
*/
m_synchronized = false;
__DMB();
m_last_sync = sync_time;
__DMB();
m_synchronized = true;
nrf_802154_hp_timer_sync_prepare();
nrf_802154_lp_timer_sync_start_at(m_last_sync.lp_timer_time,
m_drift_known ? RESYNC_TIME : FIRST_RESYNC_TIME);
}
else
{
nrf_802154_hp_timer_sync_prepare();
nrf_802154_lp_timer_sync_start_now();
}
}
#else // NRF_802154_FRAME_TIMESTAMP_ENABLED
void nrf_802154_timer_coord_init(void)
{
// Intentionally empty
}
void nrf_802154_timer_coord_uninit(void)
{
// Intentionally empty
}
void nrf_802154_timer_coord_start(void)
{
// Intentionally empty
}
void nrf_802154_timer_coord_stop(void)
{
// Intentionally empty
}
void nrf_802154_timer_coord_timestamp_prepare(uint32_t event_addr)
{
(void)event_addr;
// Intentionally empty
}
bool nrf_802154_timer_coord_timestamp_get(uint32_t * p_timestamp)
{
(void)p_timestamp;
// Intentionally empty
return false;
}
#endif // NRF_802154_FRAME_TIMESTAMP_ENABLED

View file

@ -1,115 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines the Timer Coordinator interface.
*
*/
#ifndef NRF_802154_TIMER_COORD_H_
#define NRF_802154_TIMER_COORD_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_timer_coord Timer Coordinator
* @{
* @ingroup nrf_802154
* @brief Timer Coordinator interface.
*
* Timer Coordinator is responsible to synchronize and coordinate operations of the Low Power timer
* that counts absolute time and the High Precision timer that counts time relative to a timeslot.
*/
/**
* @brief Initialize the Timer Coordinator module.
*
*/
void nrf_802154_timer_coord_init(void);
/**
* @brief Uninitialize the Timer Coordinator module.
*
*/
void nrf_802154_timer_coord_uninit(void);
/**
* @brief Start the Timer Coordinator.
*
* This function starts the HP timer and synchronizes it with the LP timer.
*
* Started Timer Coordinator resynchronizes automatically in constant interval.
*/
void nrf_802154_timer_coord_start(void);
/**
* @brief Stop the Timer Coordinator.
*
* This function stops the HP timer.
*/
void nrf_802154_timer_coord_stop(void);
/**
* @brief Prepare getting precise timestamp of given event.
*
* @param[in] event_addr Address of the peripheral register corresponding to the event that
* should be timestamped.
*/
void nrf_802154_timer_coord_timestamp_prepare(uint32_t event_addr);
/**
* @brief Get timestamp of the recently prepared event.
*
* If recently prepared event occurred a few times since preparation, this function returns
* timestamp of the first occurrence.
* If the requested event did not occur since preparation or HP timer is not synchronized, this
* function returns false.
*
* @param[out] p_timestamp Precise absolute timestamp of recently prepared event [us].
*
* @retval true Timestamp is available.
* @retval false Timestamp is unavailable.
*/
bool nrf_802154_timer_coord_timestamp_get(uint32_t * p_timestamp);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_TIMER_COORD_H_ */

View file

@ -1,136 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_TYPES_H__
#define NRF_802154_TYPES_H__
#include <stdint.h>
#include "hal/nrf_radio.h"
/**
* @defgroup nrf_802154_types Type definitions used in the 802.15.4 driver.
* @{
* @ingroup nrf_802154
* @brief Definitions of types used in the 802.15.4 driver.
*/
/**
* @brief States of the driver.
*/
typedef uint8_t nrf_802154_state_t;
#define NRF_802154_STATE_INVALID 0x01 // !< Radio in an invalid state.
#define NRF_802154_STATE_SLEEP 0x02 // !< Radio in sleep state.
#define NRF_802154_STATE_RECEIVE 0x03 // !< Radio in receive state.
#define NRF_802154_STATE_TRANSMIT 0x04 // !< Radio in transmit state.
#define NRF_802154_STATE_ENERGY_DETECTION 0x05 // !< Radio in energy detection state.
#define NRF_802154_STATE_CCA 0x06 // !< Radio in CCA state.
#define NRF_802154_STATE_CONTINUOUS_CARRIER 0x07 // !< Radio in continuous carrier state.
/**
* @brief Errors reported during frame transmission.
*/
typedef uint8_t nrf_802154_tx_error_t;
#define NRF_802154_TX_ERROR_NONE 0x00 // !< There is no transmit error.
#define NRF_802154_TX_ERROR_BUSY_CHANNEL 0x01 // !< CCA reported busy channel prior to transmission.
#define NRF_802154_TX_ERROR_INVALID_ACK 0x02 // !< Received ACK frame is other than expected.
#define NRF_802154_TX_ERROR_NO_MEM 0x03 // !< No receive buffer is available to receive an ACK.
#define NRF_802154_TX_ERROR_TIMESLOT_ENDED 0x04 // !< Radio timeslot ended during transmission procedure.
#define NRF_802154_TX_ERROR_NO_ACK 0x05 // !< ACK frame was not received during timeout period.
#define NRF_802154_TX_ERROR_ABORTED 0x06 // !< Procedure was aborted by another driver operation with FORCE priority.
#define NRF_802154_TX_ERROR_TIMESLOT_DENIED 0x07 // !< Transmission did not start due to denied timeslot request.
/**
* @brief Possible errors during frame reception.
*/
typedef uint8_t nrf_802154_rx_error_t;
#define NRF_802154_RX_ERROR_NONE 0x00 // !< There is no receive error.
#define NRF_802154_RX_ERROR_INVALID_FRAME 0x01 // !< Received a malformed frame.
#define NRF_802154_RX_ERROR_INVALID_FCS 0x02 // !< Received a frame with invalid checksum.
#define NRF_802154_RX_ERROR_INVALID_DEST_ADDR 0x03 // !< Received a frame with mismatched destination address.
#define NRF_802154_RX_ERROR_RUNTIME 0x04 // !< A runtime error occurred (for example, CPU was held for too long).
#define NRF_802154_RX_ERROR_TIMESLOT_ENDED 0x05 // !< Radio timeslot ended during frame reception.
#define NRF_802154_RX_ERROR_ABORTED 0x06 // !< Procedure was aborted by another driver operation with FORCE priority.
#define NRF_802154_RX_ERROR_DELAYED_TIMESLOT_DENIED 0x07 // !< Delayed reception request was rejected due to denied timeslot request.
#define NRF_802154_RX_ERROR_DELAYED_TIMEOUT 0x08 // !< Frame not received during delayed reception time slot.
#define NRF_802154_RX_ERROR_INVALID_LENGTH 0x09 // !< Received a frame with invalid length.
/**
* @brief Possible errors during energy detection.
*/
typedef uint8_t nrf_802154_ed_error_t;
#define NRF_802154_ED_ERROR_ABORTED 0x01 // !< Procedure was aborted by another driver operation with FORCE priority.
/**
* @brief Possible errors during CCA procedure.
*/
typedef uint8_t nrf_802154_cca_error_t;
#define NRF_802154_CCA_ERROR_ABORTED 0x01 // !< Procedure was aborted by another driver operation with FORCE priority.
/**
* @brief Possible errors during sleep procedure call.
*/
typedef uint8_t nrf_802154_sleep_error_t;
#define NRF_802154_SLEEP_ERROR_NONE 0x00 // !< There is no error.
#define NRF_802154_SLEEP_ERROR_BUSY 0x01 // !< The driver cannot enter sleep state due to ongoing operation.
/**
* @brief Termination level selected for a particular request.
*
* Each request can terminate an ongoing operation. This type selects which operation should be
* aborted by a given request.
*/
typedef uint8_t nrf_802154_term_t;
#define NRF_802154_TERM_NONE 0x00 // !< Request is skipped if another operation is ongoing.
#define NRF_802154_TERM_802154 0x01 // !< Request terminates ongoing 802.15.4 operation.
/**
* @brief Structure for configuring CCA.
*/
typedef struct
{
nrf_radio_cca_mode_t mode; // !< CCA mode.
uint8_t ed_threshold; // !< CCA energy busy threshold. Not used in NRF_RADIO_CCA_MODE_CARRIER.
uint8_t corr_threshold; // !< CCA correlator busy threshold. Not used in NRF_RADIO_CCA_MODE_ED.
uint8_t corr_limit; // !< Limit of occurrences above CCA correlator busy threshold. Not used in NRF_RADIO_CCA_MODE_ED.
} nrf_802154_cca_cfg_t;
/**
*@}
**/
#endif // NRF_802154_TYPES_H__

View file

@ -1,159 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_UTILS_H__
#define NRF_802154_UTILS_H__
#include <assert.h>
#include <stdint.h>
#include "nrf.h"
/**
* @defgroup nrf_802154_utils Utils definitions used in the 802.15.4 driver.
* @{
* @ingroup nrf_802154
* @brief Definitions of utils used in the 802.15.4 driver.
*/
/**@brief RTC clock frequency. */
#define NRF_802154_RTC_FREQUENCY 32768UL
/**@brief Defines number of microseconds in one second. */
#define NRF_802154_US_PER_S 1000000ULL
/**@brief Number of microseconds in one RTC tick. (rounded up) */
#define NRF_802154_US_PER_TICK NRF_802154_RTC_TICKS_TO_US(1)
/**@brief Number of bits to shift RTC_FREQUENCY and US_PER_S to achieve division by greatest common divisor. */
#define NRF_802154_FREQUENCY_US_PER_S_GCD_BITS 6
/**@brief Ceil division helper */
#define NRF_802154_DIVIDE_AND_CEIL(A, B) (((A) + (B)-1) / (B))
/**@brief RTC ticks to us conversion. */
#define NRF_802154_RTC_TICKS_TO_US(ticks) \
NRF_802154_DIVIDE_AND_CEIL( \
(ticks) * (NRF_802154_US_PER_S >> NRF_802154_FREQUENCY_US_PER_S_GCD_BITS), \
(NRF_802154_RTC_FREQUENCY >> NRF_802154_FREQUENCY_US_PER_S_GCD_BITS))
static inline uint64_t NRF_802154_US_TO_RTC_TICKS(uint64_t time)
{
uint64_t t1, u1;
uint64_t result;
/* The required range for time is [0..315360000000000], and the calculation below are
verified to work within broader range [0...2^49 ~ 17 years]
This first step in the calculation is to find out how many units
of 15625 us there are in the input_us, because 512 RTC units
corresponds _exactly_ to 15625 us. The calculation we want to do is therefore
t1 = time / 15625, but division is slow and therefore we want to calculate
t1 = time * k instead. The constant k is 1/15625 shifted up by as many bits
as we can without causing overflow during the calculation.
49 bits are needed to store the maximum value that time can have, and the
lowest 13 bits in that value can be shifted away because a minimum of 14 bits
are needed to store the divisor.
This means that time can be reduced to 49 - 13 = 36 bits to make space
for k.
The most suitable number of shift for the value 1 / 15625 = 0.000064
(binary 0.00000000000001000011000110111101111...) is 41, because that results
in a 28 bits number that does not cause overflow in the multiplication.
(2^41)/15625) is equal to 0x8637bd0, and is written in hexadecimal representation
to show the bit width of the number. Shifting is limited to 41 bits because:
1 The time uses up to 49 bits, and
2) The time can only be shifted down 13 bits to avoid shifting away
a full unit of 15625 microseconds, and
3) The maximum value of the calculation would otherwise overflow (i.e.
(315360000000000 >> 13) * 0x8637bd0 = 0x4b300bfcd0aefde0, would no longer be less than
0Xffffffffffffffff).
There is a possible loss of precision so that t1 will be up to 93*15625 _smaller_
than the accurate number. This is taken into account in the next step.
*/
t1 = ((time >> 13) * 0x8637bd0) >> 28; // ((time >> 13) * (2^41 / 15625)) >> (41 - 13)
result = t1 * 512;
t1 = time - t1 * 15625;
/* This second step of the calculation is to find out how many RTC units there are
still left in the remaining microseconds.
(2^56)/15625) is equal to 0x431bde82d7b, and is written in hexadecimal representation
to show the bit width of the number. Shifting 56 bits is determined by the worst
case value of t1. The constant is selected by using the same methodology as in the
first step of the calculation above.
The possible loss of precision in the calculation above can make t1 93*15625 lower
than it should have been here. The worst case found is that t1 can be 1453125, and
therefore there is no overflow in the calculation
1453125 * 0x431bde82d7b = 0x5cfffffffff76627 (i.e. it is less than 0xffffffffffffffff).
15625 below is the binary representation of 30.51757813 (11110.100001001)
scaled up by 2^9, and the calculation below are therefore using that scale.
Rounding up to the nearest RTC tick is done by adding the value of the least
significant bits of the fraction (i.e. adding the value of bits 1..47 of the scaled
up timer unit size (2^47)) to the calculated value before scaling the final
value down to RTC ticks.*/
// ceil((time * (2^56 / 15625)) >> (56 - 9))
assert(t1 <= 1453125);
u1 = (t1 * 0x431bde82d7b); // (time * (2^56 / 15625))
u1 += 0x7fffffffffff; // round up
u1 >>= 47; // ceil(u1 >> (56 - 9))
result += u1;
return result;
}
/**@brief Checks if the provided interrupt is currently enabled.
*
* @note This function is valid only for ARM Cortex-M4 core.
*
* @params IRQn Interrupt number.
*
* @returns Zero if interrupt is disabled, non-zero value otherwise.
*/
static inline uint32_t nrf_is_nvic_irq_enabled(IRQn_Type IRQn)
{
return (NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)]) &
((uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)));
}
/**
*@}
**/
#endif // NRF_802154_UTILS_H__

View file

@ -1,131 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines Clock Abstraction Layer for the 802.15.4 driver.
*
* Clock Abstraction Layer can be used by other modules to start and stop nRF52840 clocks.
*
* It is used by Radio Arbiter clients (RAAL) to start HF clock when entering continuous mode
* and stop HF clock after continuous mode exit.
*
* It is used by standalone Low Power Timer Abstraction Layer implementation
* to start LF clock during initialization.
*
*/
#ifndef NRF_802154_CLOCK_H_
#define NRF_802154_CLOCK_H_
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_clock Clock Abstraction Layer for the 802.15.4 driver
* @{
* @ingroup nrf_802154_clock
* @brief Clock Abstraction Layer interface for the 802.15.4 driver.
*
*/
/**
* @brief Initialize the clock driver.
*/
void nrf_802154_clock_init(void);
/**
* @brief Deinitialize the clock driver.
*/
void nrf_802154_clock_deinit(void);
/**
* @brief Start High Frequency Clock.
*
* This function is asynchronous. It should request ramping up of HF clock and exit. When HF clock
* is ready @sa nrf_802154_hfclk_ready() should be called.
*/
void nrf_802154_clock_hfclk_start(void);
/**
* @brief Stop High Frequency Clock.
*/
void nrf_802154_clock_hfclk_stop(void);
/**
* @brief Check if High Frequency Clock is running.
*
* @retval true If High Frequency Clock is running.
* @retval false If High Frequency Clock is not running.
*/
bool nrf_802154_clock_hfclk_is_running(void);
/**
* @brief Start Low Frequency Clock.
*
* This function is asynchronous. It should request ramping up of LF clock and exit. When LF clock
* is ready @sa nrf_802154_lfclk_ready() should be called.
*/
void nrf_802154_clock_lfclk_start(void);
/**
* @brief Stop Low Frequency Clock.
*/
void nrf_802154_clock_lfclk_stop(void);
/**
* @brief Check if Low Frequency Clock is running.
*
* @retval true If Low Frequency Clock is running.
* @retval false If Low Frequency Clock is not running.
*/
bool nrf_802154_clock_lfclk_is_running(void);
/**
* @brief Callback executed when High Frequency Clock is ready.
*/
extern void nrf_802154_clock_hfclk_ready(void);
/**
* @brief Callback executed when Low Frequency Clock is ready.
*/
extern void nrf_802154_clock_lfclk_ready(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_CLOCK_H_ */

View file

@ -1,123 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 Clock Abstraction Layer without any driver.
*
* This implementation uses directly CLOCK hardware registers.
*/
#include "nrf_802154_clock.h"
#include <nrf.h>
#include <hal/nrf_clock.h>
#include "nrf_802154_config.h"
void nrf_802154_clock_init(void)
{
nrf_clock_lf_src_set(NRF_802154_CLOCK_LFCLK_SOURCE);
NVIC_SetPriority(POWER_CLOCK_IRQn, NRF_802154_CLOCK_IRQ_PRIORITY);
NVIC_ClearPendingIRQ(POWER_CLOCK_IRQn);
NVIC_EnableIRQ(POWER_CLOCK_IRQn);
nrf_clock_int_enable(NRF_CLOCK_INT_HF_STARTED_MASK);
nrf_clock_int_enable(NRF_CLOCK_INT_LF_STARTED_MASK);
}
void nrf_802154_clock_deinit(void)
{
NVIC_DisableIRQ(POWER_CLOCK_IRQn);
NVIC_ClearPendingIRQ(POWER_CLOCK_IRQn);
nrf_clock_int_disable(NRF_CLOCK_INT_HF_STARTED_MASK);
nrf_clock_int_disable(NRF_CLOCK_INT_LF_STARTED_MASK);
}
void nrf_802154_clock_hfclk_start(void)
{
nrf_clock_event_clear(NRF_CLOCK_EVENT_HFCLKSTARTED);
nrf_clock_task_trigger(NRF_CLOCK_TASK_HFCLKSTART);
}
void nrf_802154_clock_hfclk_stop(void)
{
nrf_clock_task_trigger(NRF_CLOCK_TASK_HFCLKSTOP);
}
bool nrf_802154_clock_hfclk_is_running(void)
{
return nrf_clock_hf_is_running(NRF_CLOCK_HFCLK_HIGH_ACCURACY);
}
void nrf_802154_clock_lfclk_start(void)
{
nrf_clock_event_clear(NRF_CLOCK_EVENT_LFCLKSTARTED);
nrf_clock_task_trigger(NRF_CLOCK_TASK_LFCLKSTART);
}
void nrf_802154_clock_lfclk_stop(void)
{
nrf_clock_task_trigger(NRF_CLOCK_TASK_LFCLKSTOP);
}
bool nrf_802154_clock_lfclk_is_running(void)
{
return nrf_clock_lf_is_running();
}
void POWER_CLOCK_IRQHandler(void)
{
if (nrf_clock_event_check(NRF_CLOCK_EVENT_HFCLKSTARTED))
{
nrf_clock_event_clear(NRF_CLOCK_EVENT_HFCLKSTARTED);
nrf_802154_clock_hfclk_ready();
}
if (nrf_clock_event_check(NRF_CLOCK_EVENT_LFCLKSTARTED))
{
nrf_clock_event_clear(NRF_CLOCK_EVENT_LFCLKSTARTED);
nrf_802154_clock_lfclk_ready();
}
}
__WEAK void nrf_802154_clock_hfclk_ready(void)
{
// Intentionally empty.
}
__WEAK void nrf_802154_clock_lfclk_ready(void)
{
// Intentionally empty.
}

View file

@ -1,114 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 HF Clock abstraction with SDK driver.
*
* This implementation uses clock driver implementation from SDK.
*/
#include "nrf_802154_clock.h"
#include <stddef.h>
#include <compiler_abstraction.h>
#include <nrf_drv_clock.h>
static void clock_handler(nrf_drv_clock_evt_type_t event);
static nrf_drv_clock_handler_item_t m_clock_handler =
{
.p_next = NULL,
.event_handler = clock_handler,
};
static void clock_handler(nrf_drv_clock_evt_type_t event)
{
if (event == NRF_DRV_CLOCK_EVT_HFCLK_STARTED)
{
nrf_802154_clock_hfclk_ready();
}
if (event == NRF_DRV_CLOCK_EVT_LFCLK_STARTED)
{
nrf_802154_clock_lfclk_ready();
}
}
void nrf_802154_clock_init(void)
{
nrf_drv_clock_init();
}
void nrf_802154_clock_deinit(void)
{
nrf_drv_clock_uninit();
}
void nrf_802154_clock_hfclk_start(void)
{
nrf_drv_clock_hfclk_request(&m_clock_handler);
}
void nrf_802154_clock_hfclk_stop(void)
{
nrf_drv_clock_hfclk_release();
}
bool nrf_802154_clock_hfclk_is_running(void)
{
return nrf_drv_clock_hfclk_is_running();
}
void nrf_802154_clock_lfclk_start(void)
{
nrf_drv_clock_lfclk_request(&m_clock_handler);
}
void nrf_802154_clock_lfclk_stop(void)
{
nrf_drv_clock_lfclk_release();
}
bool nrf_802154_clock_lfclk_is_running(void)
{
return nrf_drv_clock_lfclk_is_running();
}
__WEAK void nrf_802154_clock_hfclk_ready(void)
{
// Intentionally empty.
}
__WEAK void nrf_802154_clock_lfclk_ready(void)
{
// Intentionally empty.
}

View file

@ -1,129 +0,0 @@
/* Copyright (c) 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 HF Clock abstraction with Zephyr API.
*
* This implementation uses Zephyr API for clock management.
*/
#include "nrf_802154_clock.h"
#include <stddef.h>
#include <compiler_abstraction.h>
#include <drivers/clock_control/nrf_clock_control.h>
#include <drivers/clock_control.h>
static bool hfclk_is_running;
static bool lfclk_is_running;
void nrf_802154_clock_init(void)
{
/* Intentionally empty. */
}
void nrf_802154_clock_deinit(void)
{
/* Intentionally empty. */
}
void nrf_802154_clock_hfclk_start(void)
{
struct device *clk_m16;
clk_m16 = device_get_binding(DT_INST_0_NORDIC_NRF_CLOCK_LABEL "_16M");
__ASSERT_NO_MSG(clk_m16 != NULL);
clock_control_on(clk_m16, (void *)1); /* Blocking call. */
hfclk_is_running = true;
nrf_802154_clock_hfclk_ready();
}
void nrf_802154_clock_hfclk_stop(void)
{
struct device *clk_m16;
clk_m16 = device_get_binding(DT_INST_0_NORDIC_NRF_CLOCK_LABEL "_16M");
__ASSERT_NO_MSG(clk_m16 != NULL);
hfclk_is_running = false;
clock_control_off(clk_m16, NULL);
}
bool nrf_802154_clock_hfclk_is_running(void)
{
return hfclk_is_running;
}
void nrf_802154_clock_lfclk_start(void)
{
struct device *clk_k32;
clk_k32 = device_get_binding(DT_INST_0_NORDIC_NRF_CLOCK_LABEL "_32K");
__ASSERT_NO_MSG(clk_k32 != NULL);
clock_control_on(clk_k32, (void *)CLOCK_CONTROL_NRF_K32SRC);
lfclk_is_running = true;
nrf_802154_clock_lfclk_ready();
}
void nrf_802154_clock_lfclk_stop(void)
{
struct device *clk_k32;
clk_k32 = device_get_binding(DT_INST_0_NORDIC_NRF_CLOCK_LABEL "_32K");
__ASSERT_NO_MSG(clk_k32 != NULL);
lfclk_is_running = false;
clock_control_off(clk_k32, NULL);
}
bool nrf_802154_clock_lfclk_is_running(void)
{
return lfclk_is_running;
}
__WEAK void nrf_802154_clock_hfclk_ready(void)
{
/* Intentionally empty. */
}
__WEAK void nrf_802154_clock_lfclk_ready(void)
{
/* Intentionally empty. */
}

View file

@ -1,141 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file contains implementation of the nRF 802.15.4 high precision timer abstraction.
*
* This implementation is built on top of the TIMER peripheral.
* If SoftDevice RAAL is in use the TIMER peripheral is shared between RAAL and this module.
*
*/
#include "nrf_802154_hp_timer.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <hal/nrf_timer.h>
#include <nrf.h>
#include "nrf_802154_config.h"
/**@brief Timer instance. */
#define TIMER NRF_TIMER0
/**@brief Timer compare channel definitions. */
#define TIMER_CC_CAPTURE NRF_TIMER_CC_CHANNEL1
#define TIMER_CC_CAPTURE_TASK NRF_TIMER_TASK_CAPTURE1
#define TIMER_CC_SYNC NRF_TIMER_CC_CHANNEL2
#define TIMER_CC_SYNC_TASK NRF_TIMER_TASK_CAPTURE2
#define TIMER_CC_SYNC_EVENT NRF_TIMER_EVENT_COMPARE2
#define TIMER_CC_SYNC_INT NRF_TIMER_INT_COMPARE2_MASK
#define TIMER_CC_EVT NRF_TIMER_CC_CHANNEL3
#define TIMER_CC_EVT_TASK NRF_TIMER_TASK_CAPTURE3
#define TIMER_CC_EVT_INT NRF_TIMER_INT_COMPARE3_MASK
/**@brief Unexpected value in the sync compare channel. */
static uint32_t m_unexpected_sync;
/**@brief Get current time on the Timer. */
static inline uint32_t timer_time_get(void)
{
nrf_timer_task_trigger(TIMER, TIMER_CC_CAPTURE_TASK);
return nrf_timer_cc_read(TIMER, TIMER_CC_CAPTURE);
}
void nrf_802154_hp_timer_init(void)
{
// Intentionally empty
}
void nrf_802154_hp_timer_deinit(void)
{
nrf_timer_task_trigger(TIMER, NRF_TIMER_TASK_SHUTDOWN);
}
void nrf_802154_hp_timer_start(void)
{
#if !RAAL_SOFTDEVICE && !RAAL_SIMULATOR
nrf_timer_mode_set(TIMER, NRF_TIMER_MODE_TIMER);
nrf_timer_bit_width_set(TIMER, NRF_TIMER_BIT_WIDTH_32);
nrf_timer_frequency_set(TIMER, NRF_TIMER_FREQ_1MHz);
nrf_timer_task_trigger(TIMER, NRF_TIMER_TASK_START);
#endif // !RAAL_SOFTDEVICE && !RAAL_SIMULATOR
}
void nrf_802154_hp_timer_stop(void)
{
#if !RAAL_SOFTDEVICE && !RAAL_SIMULATOR
nrf_timer_task_trigger(TIMER, NRF_TIMER_TASK_SHUTDOWN);
#endif // !RAAL_SOFTDEVICE && !RAAL_SIMULATOR
}
uint32_t nrf_802154_hp_timer_sync_task_get(void)
{
return (uint32_t)nrf_timer_task_address_get(TIMER, TIMER_CC_SYNC_TASK);
}
void nrf_802154_hp_timer_sync_prepare(void)
{
uint32_t past_time = timer_time_get() - 1;
m_unexpected_sync = past_time;
nrf_timer_cc_write(TIMER, TIMER_CC_SYNC, past_time);
}
bool nrf_802154_hp_timer_sync_time_get(uint32_t * p_timestamp)
{
bool result = false;
uint32_t sync_time = nrf_timer_cc_read(TIMER, TIMER_CC_SYNC);
assert(p_timestamp != NULL);
if (sync_time != m_unexpected_sync)
{
*p_timestamp = sync_time;
result = true;
}
return result;
}
uint32_t nrf_802154_hp_timer_timestamp_task_get(void)
{
return (uint32_t)nrf_timer_task_address_get(TIMER, TIMER_CC_EVT_TASK);
}
uint32_t nrf_802154_hp_timer_timestamp_get(void)
{
return nrf_timer_cc_read(TIMER, TIMER_CC_EVT);
}

View file

@ -1,145 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines API or High Precision Timer for the 802.15.4 driver.
*
*/
#ifndef NRF_802154_HP_TIMER_H_
#define NRF_802154_HP_TIMER_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_hp_timer High Precision Timer for the 802.15.4 driver
* @{
* @ingroup nrf_802154_hp_timer
* @brief High Precision Timer for the 802.15.4 driver.
*
* High Precision Timer is a timer that is used only when the radio is in use. This timer is not
* used when the radio is in the sleep mode or out of RAAL timeslots. This timer should provide at
* least 1us precision. It is intended to be used for precise frame timestamps or synchronous radio
* operations.
*
* @note High Precision Timer is a relative timer. To use it as absolute timer it must be
* synchronized with the Low Power Timer.
*
*/
/**
* @brief Initialize the timer.
*/
void nrf_802154_hp_timer_init(void);
/**
* @brief Uninitialize the timer.
*/
void nrf_802154_hp_timer_deinit(void);
/**
* @brief Start the timer.
*
* The timer starts counting when this command is called.
*/
void nrf_802154_hp_timer_start(void);
/**
* @brief Stop the timer.
*
* The timer stops counting and enters low power mode.
*/
void nrf_802154_hp_timer_stop(void);
/**
* @brief Get value indicated by the timer right now.
*
* @note Returned value is relative to the @ref nrf_802154_hp_timer_start call time. It is not
* synchronized with the lp timer.
*
* @returns Current timer value [us].
*/
uint32_t nrf_802154_hp_timer_current_time_get(void);
/**
* @brief Get task used to synchronize this timer with the LP timer.
*
* @returns Address of the task.
*/
uint32_t nrf_802154_hp_timer_sync_task_get(void);
/**
* @brief Configure the timer to detect if sync task was triggered.
*/
void nrf_802154_hp_timer_sync_prepare(void);
/**
* @brief Get timestamp of the synchronization event.
*
* @param[out] p_timestamp Timestamp of the synchronization event.
*
* @retval true Synchronization was performed and @p p_timestamp is valid.
* @retval false Synchronization was not performed. @p p_timestamp was not modified.
*/
bool nrf_802154_hp_timer_sync_time_get(uint32_t * p_timestamp);
/**
* @brief Get task used to make timestamp of an event.
*
* This function should be used to configure PPI.
* This function configures the timer in order to detect if returned task was triggered to return
* valid value by the @ref nrf_802154_hp_timer_timestamp_get.
*
* @returns Address of the task.
*/
uint32_t nrf_802154_hp_timer_timestamp_task_get(void);
/**
* @brief Get timestamp of last event.
*
* @returns Timestamp of last event that triggered the @ref nrf_802154_hp_timer_timestamp_task_get
* task.
*/
uint32_t nrf_802154_hp_timer_timestamp_get(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_HP_TIMER_H_ */

View file

@ -1,208 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines Low Power Timer Abstraction Layer for the 802.15.4 driver.
*
*/
#ifndef NRF_802154_LP_TIMER_API_H_
#define NRF_802154_LP_TIMER_API_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_timer Low Power Timer Abstraction Layer for the 802.15.4 driver
* @{
* @ingroup nrf_802154_timer
* @brief Low Power Timer Abstraction Layer interface for the 802.15.4 driver.
*
* Low Power Timer Abstraction Layer is an abstraction layer of timer that is meant to be used by
* the nRF 802.15.4 driver. This timer should provide low latency (max 100 us) in order to allow
* implementation in the driver code features like:
* * Timing out waiting for ACK frame
* * SIFS and LIFS
* * CSMA/CA
* * CSL
* * Auto polling by rx-off-when-idle devices
*
* @note Most of Low Power Timer Abstraction Layer API should not be called directly by 802.15.4 driver
* modules. This API is used by the Timer Scheduler module included in the driver and other
* modules should use Timer Scheduler API. Exception from above rule are initialization and
* deinitialization functions @sa nrf_802154_lp_timer_init()
* @sa nrf_802154_lp_timer_deinit() and critical section management
* @sa nrf_802154_lp_timer_critical_section_enter()
* @sa nrf_802154_lp_timer_critical_section_exit() as these functions are called from
* nrf_802154_critical_section module and from global initialization functions
* @sa nrf_802154_init() @sa nrf_802154_deinit().
*/
/**
* @brief Initialize the Timer.
*/
void nrf_802154_lp_timer_init(void);
/**
* @brief Uninitialize the Timer.
*/
void nrf_802154_lp_timer_deinit(void);
/**
* @brief Enter critical section of the timer.
*
* In critical section timer cannot execute @sa nrf_802154_lp_timer_fired() function.
*
* @note Critical section cannot be nested.
*/
void nrf_802154_lp_timer_critical_section_enter(void);
/**
* @brief Exit critical section of the timer.
*
* In critical section timer cannot execute @sa nrf_802154_lp_timer_fired() function.
*
* @note Critical section cannot be nested.
*/
void nrf_802154_lp_timer_critical_section_exit(void);
/**
* @brief Get current time.
*
* Prior to getting current time, Timer must be initialized @sa nrf_802154_lp_timer_init().
* There are no other requirements that must be fulfilled before using this function.
*
* @return Current time in microseconds [us].
*/
uint32_t nrf_802154_lp_timer_time_get(void);
/**
* @brief Get granularity of currently used timer.
*
* This function may be used to round up/down time calculations.
*
* @return Timer granularity in microseconds [us].
*/
uint32_t nrf_802154_lp_timer_granularity_get(void);
/**
* @brief Start one-shot timer that expires at specified time.
*
* Start one-shot timer that will expire @p dt microseconds after @p t0 time.
* If timer is running when this function is called, previously running timer will be stopped
* automatically.
*
* On timer expiration @sa nrf_802154_lp_timer_fired function will be called.
* Timer automatically stops after expiration.
*
* @param[in] t0 Number of microseconds representing timer start time.
* @param[in] dt Time of timer expiration as time elapsed from @p t0 [us].
*/
void nrf_802154_lp_timer_start(uint32_t t0, uint32_t dt);
/**
* @brief Stop currently running timer.
*/
void nrf_802154_lp_timer_stop(void);
/**
* @brief Check if timer is currently running.
*
* @retval true Timer is running.
* @retval false Timer is not running.
*/
bool nrf_802154_lp_timer_is_running(void);
/**
* @brief Start one-shot synchronization timer that expires at nearest possible timepoint.
*
* On timer expiration @ref nrf_802154_lp_timer_synchronized function will be called and
* event returned by @ref nrf_802154_lp_timer_sync_event_get will be triggered.
*
* @note @ref nrf_802154_lp_timer_synchronized may be called multiple times.
*/
void nrf_802154_lp_timer_sync_start_now(void);
/**
* @brief Start one-shot synchronization timer that expires at specified time.
*
* Start one-shot synchronization timer that will expire @p dt microseconds after @p t0 time.
*
* On timer expiration @ref nrf_802154_lp_timer_synchronized function will be called and
* event returned by @ref nrf_802154_lp_timer_sync_event_get will be triggered.
*
* @param[in] t0 Number of microseconds representing timer start time.
* @param[in] dt Time of timer expiration as time elapsed from @p t0 [us].
*/
void nrf_802154_lp_timer_sync_start_at(uint32_t t0, uint32_t dt);
/**
* @brief Stop currently running synchronization timer.
*/
void nrf_802154_lp_timer_sync_stop(void);
/**
* @brief Get event used to synchronize this timer with HP Timer
*
* @return Address of the peripheral register corresponding to the event that
* should be used for timers synchronization.
*/
uint32_t nrf_802154_lp_timer_sync_event_get(void);
/**
* @brief Get timestamp of the synchronization event.
*
* @return Timestamp of the synchronization event.
*/
uint32_t nrf_802154_lp_timer_sync_time_get(void);
/**
* @brief Callback executed when timer expires.
*/
extern void nrf_802154_lp_timer_fired(void);
/**
* @brief Callback executed when synchronization timer expires.
*/
extern void nrf_802154_lp_timer_synchronized(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_LP_TIMER_API_H_ */

View file

@ -1,592 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file contains standalone implementation of the nRF 802.15.4 timer abstraction.
*
* This implementation is built on top of the RTC peripheral.
*
*/
#include "nrf_802154_lp_timer.h"
#include <assert.h>
#include <hal/nrf_rtc.h>
#include <nrf.h>
#include "platform/clock/nrf_802154_clock.h"
#include "nrf_802154_config.h"
#include "nrf_802154_utils.h"
#define RTC_LP_TIMER_COMPARE_CHANNEL 0
#define RTC_LP_TIMER_COMPARE_INT_MASK NRF_RTC_INT_COMPARE0_MASK
#define RTC_LP_TIMER_COMPARE_EVENT NRF_RTC_EVENT_COMPARE_0
#define RTC_LP_TIMER_COMPARE_EVENT_MASK RTC_EVTEN_COMPARE0_Msk
#define RTC_SYNC_COMPARE_CHANNEL 1
#define RTC_SYNC_COMPARE_INT_MASK NRF_RTC_INT_COMPARE1_MASK
#define RTC_SYNC_COMPARE_EVENT NRF_RTC_EVENT_COMPARE_1
#define RTC_SYNC_COMPARE_EVENT_MASK RTC_EVTEN_COMPARE1_Msk
#define US_PER_OVERFLOW (512UL * NRF_802154_US_PER_S) ///< Time that has passed between overflow events. On full RTC speed, it occurs every 512 s.
#define MIN_RTC_COMPARE_EVENT_DT (2 * NRF_802154_US_PER_TICK) ///< Minimum time delta from now before RTC compare event is guaranteed to fire.
#define EPOCH_32BIT_US (1ULL << 32)
#define EPOCH_FROM_TIME(time) ((time) & ((uint64_t)UINT32_MAX << 32))
// Struct holding information about compare channel.
typedef struct
{
uint32_t channel; ///< Channel number
uint32_t int_mask; ///< Interrupt mask
nrf_rtc_event_t event; ///< Event
uint32_t event_mask; ///< Event mask
} compare_channel_descriptor_t;
// Enum holding all used compare channels.
typedef enum {LP_TIMER_CHANNEL, SYNC_CHANNEL, CHANNEL_CNT} compare_channel_t;
// Descriptors of all used compare channels.
static const compare_channel_descriptor_t m_cmp_ch[CHANNEL_CNT] = {{RTC_LP_TIMER_COMPARE_CHANNEL,
RTC_LP_TIMER_COMPARE_INT_MASK,
RTC_LP_TIMER_COMPARE_EVENT,
RTC_LP_TIMER_COMPARE_EVENT_MASK},
{RTC_SYNC_COMPARE_CHANNEL,
RTC_SYNC_COMPARE_INT_MASK,
RTC_SYNC_COMPARE_EVENT,
RTC_SYNC_COMPARE_EVENT_MASK}};
static uint64_t m_target_times[CHANNEL_CNT]; ///< Target time of given channel [us].
static volatile uint32_t m_offset_counter; ///< Counter of RTC overflows, incremented by 2 on each OVERFLOW event.
static volatile uint8_t m_mutex; ///< Mutex for write access to @ref m_offset_counter.
static volatile bool m_clock_ready; ///< Information that LFCLK is ready.
static volatile uint32_t m_lp_timer_irq_enabled; ///< Information that RTC interrupt was enabled while entering critical section.
static uint32_t overflow_counter_get(void);
/** @brief Non-blocking mutex for mutual write access to @ref m_offset_counter variable.
*
* @retval true Mutex was acquired.
* @retval false Mutex could not be acquired.
*/
static inline bool mutex_get(void)
{
do
{
volatile uint8_t mutex_value = __LDREXB(&m_mutex);
if (mutex_value)
{
__CLREX();
return false;
}
}
while (__STREXB(1, &m_mutex));
// Disable OVERFLOW interrupt to prevent lock-up in interrupt context while mutex is locked from lower priority context
// and OVERFLOW event flag is stil up.
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, NRF_RTC_INT_OVERFLOW_MASK);
__DMB();
return true;
}
/** @brief Release mutex. */
static inline void mutex_release(void)
{
// Re-enable OVERFLOW interrupt.
nrf_rtc_int_enable(NRF_802154_RTC_INSTANCE, NRF_RTC_INT_OVERFLOW_MASK);
__DMB();
m_mutex = 0;
}
/** @brief Check if timer shall strike.
*
* @param[in] now Current time.
*
* @retval true Timer shall strike now.
* @retval false Timer shall not strike now.
*/
static inline bool shall_strike(uint64_t now)
{
return now >= m_target_times[LP_TIMER_CHANNEL];
}
/** @brief Convert time in [us] to RTC ticks.
*
* @param[in] time Time to convert.
*
* @return Time value in RTC ticks.
*/
static inline uint64_t time_to_ticks(uint64_t time)
{
return NRF_802154_US_TO_RTC_TICKS(time);
}
/** @brief Convert RTC ticks to time in [us].
*
* @param[in] ticks RTC ticks to convert.
*
* @return Time value in [us].
*/
static inline uint64_t ticks_to_time(uint64_t ticks)
{
return NRF_802154_RTC_TICKS_TO_US(ticks);
}
/** @brief Get current value of the RTC counter.
*
* @return RTC counter value [ticks].
*/
static uint32_t counter_get(void)
{
return nrf_rtc_counter_get(NRF_802154_RTC_INSTANCE);
}
/** @brief Get RTC counter value and matching offset that represent the current time.
*
* @param[out] p_offset Offset of the current time.
* @param[out] p_counter RTC value of the current time.
*/
static void offset_and_counter_get(uint32_t * p_offset, uint32_t * p_counter)
{
uint32_t offset_1 = overflow_counter_get();
__DMB();
uint32_t rtc_value_1 = counter_get();
__DMB();
uint32_t offset_2 = overflow_counter_get();
*p_offset = offset_2;
*p_counter = (offset_1 == offset_2) ? rtc_value_1 : counter_get();
}
/** @brief Get time from given @p offset and @p counter values.
*
* @param[in] offset Offset of time to get.
* @param[in] counter RTC value representing time to get.
*
* @return Time calculated from given offset and counter [us].
*/
static uint64_t time_get(uint32_t offset, uint32_t counter)
{
return (uint64_t)offset * US_PER_OVERFLOW + ticks_to_time(counter);
}
/** @brief Get current time.
*
* @return Current time in [us].
*/
static uint64_t curr_time_get(void)
{
uint32_t offset;
uint32_t rtc_value;
offset_and_counter_get(&offset, &rtc_value);
return time_get(offset, rtc_value);
}
/** @brief Get current overflow counter and handle OVERFLOW event if present.
*
* This function returns current value of m_overflow_counter variable. If OVERFLOW event is present
* while calling this function, it is handled within it.
*
* @return Current number of OVERFLOW events since platform start.
*/
static uint32_t overflow_counter_get(void)
{
uint32_t offset;
// Get mutual access for writing to m_offset_counter variable.
if (mutex_get())
{
bool increasing = false;
// Check if interrupt was handled already.
if (nrf_rtc_event_pending(NRF_802154_RTC_INSTANCE, NRF_RTC_EVENT_OVERFLOW))
{
m_offset_counter++;
increasing = true;
__DMB();
// Mark that interrupt was handled.
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, NRF_RTC_EVENT_OVERFLOW);
// Result should be incremented. m_offset_counter will be incremented after mutex is released.
}
else
{
// Either overflow handling is not needed OR we acquired the mutex just after it was released.
// Overflow is handled after mutex is released, but it cannot be assured that m_offset_counter
// was incremented for the second time, so we increment the result here.
}
offset = (m_offset_counter + 1) / 2;
mutex_release();
if (increasing)
{
// It's virtually impossible that overflow event is pending again before next instruction is performed. It is an error condition.
assert(m_offset_counter & 0x01);
// Increment the counter for the second time, to alloww instructions from other context get correct value of the counter.
m_offset_counter++;
}
}
else
{
// Failed to acquire mutex.
if (nrf_rtc_event_pending(NRF_802154_RTC_INSTANCE,
NRF_RTC_EVENT_OVERFLOW) || (m_offset_counter & 0x01))
{
// Lower priority context is currently incrementing m_offset_counter variable.
offset = (m_offset_counter + 2) / 2;
}
else
{
// Lower priority context has already incremented m_offset_counter variable or incrementing is not needed now.
offset = m_offset_counter / 2;
}
}
return offset;
}
/** @brief Handle COMPARE event. */
static void handle_compare_match(bool skip_check)
{
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event);
// In case the target time was larger than single overflow,
// we should only strike the timer on final compare event.
if (skip_check || shall_strike(curr_time_get()))
{
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event_mask);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask);
nrf_802154_lp_timer_fired();
}
}
/**
* @brief Convert t0 and dt to 64 bit time.
*
* @note This function takes into account possible overflow of first 32 bits in current time.
*
* @return Converted time in [us].
*/
static uint64_t convert_to_64bit_time(uint32_t t0, uint32_t dt, const uint64_t * p_now)
{
uint64_t now;
now = *p_now;
// Check if 32 LSB of `now` overflowed between getting t0 and loading `now` value.
if (((uint32_t)now < t0) && ((t0 - (uint32_t)now) > (UINT32_MAX / 2)))
{
now -= EPOCH_32BIT_US;
}
else if (((uint32_t)now > t0) && (((uint32_t)now) - t0 > (UINT32_MAX / 2)))
{
now += EPOCH_32BIT_US;
}
return (EPOCH_FROM_TIME(now)) + t0 + dt;
}
/**
* @brief Round time up to multiple of the timer ticks.
*/
static uint64_t round_up_to_timer_ticks_multiply(uint64_t time)
{
uint64_t ticks = time_to_ticks(time);
uint64_t result = ticks_to_time(ticks);
return result;
}
/**
* @brief Start one-shot timer that expires at specified time on desired channel.
*
* Start one-shot timer that will expire @p dt microseconds after @p t0 time on channel @p channel.
*
* @param[in] channel Compare channel on which timer will be started.
* @param[in] t0 Number of microseconds representing timer start time.
* @param[in] dt Time of timer expiration as time elapsed from @p t0 [us].
* @param[in] p_now Pointer to data with the current time.
*/
static void timer_start_at(compare_channel_t channel,
uint32_t t0,
uint32_t dt,
const uint64_t * p_now)
{
uint64_t target_counter;
uint64_t target_time;
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[channel].int_mask);
nrf_rtc_event_enable(NRF_802154_RTC_INSTANCE, m_cmp_ch[channel].event_mask);
target_time = convert_to_64bit_time(t0, dt, p_now);
target_counter = time_to_ticks(target_time);
m_target_times[channel] = round_up_to_timer_ticks_multiply(target_time);
nrf_rtc_cc_set(NRF_802154_RTC_INSTANCE, m_cmp_ch[channel].channel, target_counter);
}
/**
* @brief Start synchronization timer at given time.
*
* @param[in] t0 Number of microseconds representing timer start time.
* @param[in] dt Time of timer expiration as time elapsed from @p t0 [us].
* @param[in] p_now Pointer to data with current time.
*/
static void timer_sync_start_at(uint32_t t0, uint32_t dt, const uint64_t * p_now)
{
timer_start_at(SYNC_CHANNEL, t0, dt, p_now);
nrf_rtc_int_enable(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].int_mask);
}
void nrf_802154_lp_timer_init(void)
{
m_offset_counter = 0;
m_target_times[LP_TIMER_CHANNEL] = 0;
m_clock_ready = false;
m_lp_timer_irq_enabled = 0;
// Setup low frequency clock.
nrf_802154_clock_lfclk_start();
while (!m_clock_ready)
{
// Intentionally empty
}
// Setup RTC timer.
NVIC_SetPriority(NRF_802154_RTC_IRQN, NRF_802154_RTC_IRQ_PRIORITY);
NVIC_ClearPendingIRQ(NRF_802154_RTC_IRQN);
NVIC_EnableIRQ(NRF_802154_RTC_IRQN);
nrf_rtc_prescaler_set(NRF_802154_RTC_INSTANCE, 0);
// Setup RTC events.
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, NRF_RTC_EVENT_OVERFLOW);
nrf_rtc_event_enable(NRF_802154_RTC_INSTANCE, RTC_EVTEN_OVRFLW_Msk);
nrf_rtc_int_enable(NRF_802154_RTC_INSTANCE, NRF_RTC_INT_OVERFLOW_MASK);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask);
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event_mask);
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event);
// Start RTC timer.
nrf_rtc_task_trigger(NRF_802154_RTC_INSTANCE, NRF_RTC_TASK_START);
}
void nrf_802154_lp_timer_deinit(void)
{
nrf_rtc_task_trigger(NRF_802154_RTC_INSTANCE, NRF_RTC_TASK_STOP);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask);
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event_mask);
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, NRF_RTC_INT_OVERFLOW_MASK);
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, RTC_EVTEN_OVRFLW_Msk);
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, NRF_RTC_EVENT_OVERFLOW);
nrf_802154_lp_timer_sync_stop();
NVIC_DisableIRQ(NRF_802154_RTC_IRQN);
NVIC_ClearPendingIRQ(NRF_802154_RTC_IRQN);
NVIC_SetPriority(NRF_802154_RTC_IRQN, 0);
nrf_802154_clock_lfclk_stop();
}
void nrf_802154_lp_timer_critical_section_enter(void)
{
if (nrf_is_nvic_irq_enabled(NRF_802154_RTC_IRQN))
{
m_lp_timer_irq_enabled = 1;
}
NVIC_DisableIRQ(NRF_802154_RTC_IRQN);
}
void nrf_802154_lp_timer_critical_section_exit(void)
{
if (m_lp_timer_irq_enabled)
{
m_lp_timer_irq_enabled = 0;
NVIC_EnableIRQ(NRF_802154_RTC_IRQN);
}
}
uint32_t nrf_802154_lp_timer_time_get(void)
{
return (uint32_t)curr_time_get();
}
uint32_t nrf_802154_lp_timer_granularity_get(void)
{
return NRF_802154_US_PER_TICK;
}
void nrf_802154_lp_timer_start(uint32_t t0, uint32_t dt)
{
uint32_t offset;
uint32_t rtc_value;
uint64_t now;
offset_and_counter_get(&offset, &rtc_value);
now = time_get(offset, rtc_value);
timer_start_at(LP_TIMER_CHANNEL, t0, dt, &now);
if (rtc_value != counter_get())
{
now = curr_time_get();
}
if (shall_strike(now + MIN_RTC_COMPARE_EVENT_DT))
{
handle_compare_match(true);
}
else
{
nrf_rtc_int_enable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask);
}
}
bool nrf_802154_lp_timer_is_running(void)
{
return nrf_rtc_int_is_enabled(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask);
}
void nrf_802154_lp_timer_stop(void)
{
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event_mask);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask);
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event);
}
void nrf_802154_lp_timer_sync_start_now(void)
{
uint32_t counter;
uint32_t offset;
uint64_t now;
do
{
offset_and_counter_get(&offset, &counter);
now = time_get(offset, counter);
timer_sync_start_at((uint32_t)now, MIN_RTC_COMPARE_EVENT_DT, &now);
}
while (counter_get() != counter);
}
void nrf_802154_lp_timer_sync_start_at(uint32_t t0, uint32_t dt)
{
uint64_t now = curr_time_get();
timer_sync_start_at(t0, dt, &now);
}
void nrf_802154_lp_timer_sync_stop(void)
{
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].event_mask);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].int_mask);
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].event);
}
uint32_t nrf_802154_lp_timer_sync_event_get(void)
{
return (uint32_t)nrf_rtc_event_address_get(NRF_802154_RTC_INSTANCE,
m_cmp_ch[SYNC_CHANNEL].event);
}
uint32_t nrf_802154_lp_timer_sync_time_get(void)
{
return (uint32_t)m_target_times[SYNC_CHANNEL];
}
void nrf_802154_clock_lfclk_ready(void)
{
m_clock_ready = true;
}
void NRF_802154_RTC_IRQ_HANDLER(void)
{
// Handle overflow.
if (nrf_rtc_event_pending(NRF_802154_RTC_INSTANCE, NRF_RTC_EVENT_OVERFLOW))
{
// Disable OVERFLOW interrupt to prevent lock-up in interrupt context while mutex is locked from lower priority context
// and OVERFLOW event flag is stil up.
// OVERFLOW interrupt will be re-enabled when mutex is released - either from this handler, or from lower priority context,
// that locked the mutex.
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, NRF_RTC_INT_OVERFLOW_MASK);
// Handle OVERFLOW event by reading current value of overflow counter.
(void)overflow_counter_get();
}
// Handle compare match.
if (nrf_rtc_int_is_enabled(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].int_mask) &&
nrf_rtc_event_pending(NRF_802154_RTC_INSTANCE, m_cmp_ch[LP_TIMER_CHANNEL].event))
{
handle_compare_match(false);
}
if (nrf_rtc_int_is_enabled(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].int_mask) &&
nrf_rtc_event_pending(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].event))
{
nrf_rtc_event_clear(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].event);
nrf_rtc_event_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].event_mask);
nrf_rtc_int_disable(NRF_802154_RTC_INSTANCE, m_cmp_ch[SYNC_CHANNEL].int_mask);
nrf_802154_lp_timer_synchronized();
}
}
__WEAK void nrf_802154_lp_timer_synchronized(void)
{
// Intentionally empty
}

View file

@ -1,62 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 timer abstraction in case timer is not used.
*
* This timer abstraction should be used only when none of driver features that use timer is enabled.
*
*/
#include "nrf_802154_lp_timer.h"
void nrf_802154_lp_timer_init(void)
{
// Intentionally empty
}
void nrf_802154_lp_timer_deinit(void)
{
// Intentionally empty
}
void nrf_802154_lp_timer_critical_section_enter(void)
{
// Intentionally empty
}
void nrf_802154_lp_timer_critical_section_exit(void)
{
// Intentionally empty
}
// Other functions from TimAL API are intentionally not implemented to detect build configuration
// problems compile-time.

View file

@ -1,77 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file contains standalone implementation of the nRF 802.15.4 timer abstraction.
*
* This implementation is built on top of the RTC peripheral.
*
*/
#include <stdint.h>
#include <kernel.h>
#include "nrf_802154_lp_timer.h"
#include "nrf_802154_utils.h"
void nrf_802154_lp_timer_init(void)
{
/* Intentionally empty. */
}
void nrf_802154_lp_timer_deinit(void)
{
/* Intentionally empty. */
}
void nrf_802154_lp_timer_critical_section_enter(void)
{
/* Intentionally empty. */
}
void nrf_802154_lp_timer_critical_section_exit(void)
{
/* Intentionally empty. */
}
uint32_t nrf_802154_lp_timer_time_get(void)
{
u64_t ticks = k_cycle_get_32();
return (u32_t)(NRF_802154_RTC_TICKS_TO_US(ticks));
}
uint32_t nrf_802154_lp_timer_granularity_get(void)
{
return NRF_802154_US_PER_TICK;
}

View file

@ -1,87 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines Thermometer Abstraction Layer for the 802.15.4 driver.
*
*/
#ifndef NRF_802154_TEMPERATURE_H_
#define NRF_802154_TEMPERATURE_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_temperature Thermometer Abstraction Layer for the 802.15.4 driver
* @{
* @ingroup nrf_802154
* @brief Thermometer Abstraction Layer interface for the 802.15.4 driver.
*
* Thermometer Abstraction Layer is an abstraction layer of thermometer that is used to correct
* RSSI, LQI, ED result and CCA threshold measurements.
*
*/
/**
* @brief Initialize thermometer.
*/
void nrf_802154_temperature_init(void);
/**
* @brief Uninitialize thermometer.
*/
void nrf_802154_temperature_deinit(void);
/**
* @brief Get current temperature.
*
* @return Current temperature [C].
*/
int8_t nrf_802154_temperature_get(void);
/**
* @brief Callback executed when temperature changes.
*/
extern void nrf_802154_temperature_changed(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_TEMPERATURE_H_ */

View file

@ -1,59 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the thermometer abstraction stub that does not use thermometer.
*
* This thermometer abstraction will cause RSSI, LQI, ED, CCA threshold errors up to 3 dBm when
* temperature of device differs more than 5 C from 20 C.
*
*/
#include "nrf_802154_temperature.h"
#include <stdint.h>
#define DEFAULT_TEMPERATURE 20 ///< Default temperature reported by this driver stub [C].
void nrf_802154_temperature_init(void)
{
// Intentionally empty
}
void nrf_802154_temperature_deinit(void)
{
// Intentionally empty
}
int8_t nrf_802154_temperature_get(void)
{
return DEFAULT_TEMPERATURE;
}

View file

@ -1,456 +0,0 @@
#include "nrf_802154_rsch.h"
#include <assert.h>
#include <stddef.h>
#include <nrf.h>
#include "nrf_802154_debug.h"
#include "nrf_802154_priority_drop.h"
#include "platform/clock/nrf_802154_clock.h"
#include "raal/nrf_raal_api.h"
#include "timer_scheduler/nrf_802154_timer_sched.h"
#define PREC_RAMP_UP_TIME 300 ///< Ramp-up time of preconditions [us]. 300 is worst case for HFclock
static volatile uint8_t m_ntf_mutex; ///< Mutex for notyfying core.
static volatile uint8_t m_ntf_mutex_monitor; ///< Mutex monitor, incremented every failed ntf mutex lock.
static volatile uint8_t m_req_mutex; ///< Mutex for requesting preconditions.
static volatile uint8_t m_req_mutex_monitor; ///< Mutex monitor, incremented every failed req mutex lock.
static volatile rsch_prio_t m_last_notified_prio; ///< Last reported approved priority level.
static volatile rsch_prio_t m_approved_prios[RSCH_PREC_CNT]; ///< Priority levels approved by each precondition.
static rsch_prio_t m_requested_prio; ///< Priority requested from all preconditions.
static rsch_prio_t m_cont_mode_prio; ///< Continuous mode priority level. If continuous mode is not requested equal to @ref RSCH_PRIO_IDLE.
typedef struct
{
rsch_prio_t prio; ///< Delayed timeslot priority level. If delayed timeslot is not scheduled equal to @ref RSCH_PRIO_IDLE.
uint32_t t0; ///< Time base of the delayed timeslot trigger time.
uint32_t dt; ///< Time delta of the delayed timeslot trigger time.
nrf_802154_timer_t timer; ///< Timer used to trigger delayed timeslot.
} dly_ts_t;
static dly_ts_t m_dly_ts[RSCH_DLY_TS_NUM];
/** @brief Non-blocking mutex for notifying core.
*
* @param[inout] p_mutex Pointer to the mutex data.
* @param[inout] p_mutex_monitor Pointer to the mutex monitor counter.
*
* @retval true Mutex was acquired.
* @retval false Mutex could not be acquired.
*/
static inline bool mutex_trylock(volatile uint8_t * p_mutex, volatile uint8_t * p_mutex_monitor)
{
do
{
uint8_t mutex_value = __LDREXB(p_mutex);
if (mutex_value)
{
__CLREX();
(*p_mutex_monitor)++;
return false;
}
}
while (__STREXB(1, p_mutex));
__DMB();
return true;
}
/** @brief Release mutex. */
static inline void mutex_unlock(volatile uint8_t * p_mutex)
{
__DMB();
*p_mutex = 0;
}
/** @brief Check maximal priority level required by any of delayed timeslots at the moment.
*
* To meet delayed timeslot timing requirements there is a time window in which radio
* preconditions should be requested. This function is used to prevent releasing preconditions
* in this time window.
*
* @return Maximal priority level required by delayed timeslots.
*/
static rsch_prio_t max_prio_for_delayed_timeslot_get(void)
{
rsch_prio_t result = RSCH_PRIO_IDLE;
uint32_t now = nrf_802154_timer_sched_time_get();
for (uint32_t i = 0; i < RSCH_DLY_TS_NUM; i++)
{
dly_ts_t * p_dly_ts = &m_dly_ts[i];
uint32_t t0 = p_dly_ts->t0;
uint32_t dt = p_dly_ts->dt - PREC_RAMP_UP_TIME -
nrf_802154_timer_sched_granularity_get();
if ((p_dly_ts->prio > result) && !nrf_802154_timer_sched_time_is_in_future(now, t0, dt))
{
result = p_dly_ts->prio;
}
}
return result;
}
static rsch_prio_t required_prio_lvl_get(void)
{
rsch_prio_t result = max_prio_for_delayed_timeslot_get();
if (m_cont_mode_prio > result)
{
result = m_cont_mode_prio;
}
return result;
}
/** @brief Set approved priority level @p prio on given precondition @p prec.
*
* When requested priority level equals to the @ref RSCH_PRIO_IDLE this function will approve only
* the @ref RSCH_PRIO_IDLE priority level and drop other approved levels silently.
*
* @param[in] prec Precondition which state will be changed.
* @param[in] prio Approved priority level for given precondition.
*/
static inline void prec_approved_prio_set(rsch_prec_t prec, rsch_prio_t prio)
{
assert(prec <= RSCH_PREC_CNT);
if ((m_requested_prio == RSCH_PRIO_IDLE) && (prio != RSCH_PRIO_IDLE))
{
// Ignore approved precondition - it was not requested.
return;
}
assert((m_approved_prios[prec] != prio) || (prio == RSCH_PRIO_IDLE));
m_approved_prios[prec] = prio;
}
/** @brief Request all preconditions.
*/
static inline void all_prec_update(void)
{
rsch_prio_t prev_prio;
rsch_prio_t new_prio;
uint8_t monitor;
do
{
if (!mutex_trylock(&m_req_mutex, &m_req_mutex_monitor))
{
return;
}
monitor = m_req_mutex_monitor;
prev_prio = m_requested_prio;
new_prio = required_prio_lvl_get();
if (prev_prio != new_prio)
{
m_requested_prio = new_prio;
if (new_prio == RSCH_PRIO_IDLE)
{
nrf_802154_priority_drop_hfclk_stop();
prec_approved_prio_set(RSCH_PREC_HFCLK, RSCH_PRIO_IDLE);
nrf_raal_continuous_mode_exit();
prec_approved_prio_set(RSCH_PREC_RAAL, RSCH_PRIO_IDLE);
}
else
{
nrf_802154_priority_drop_hfclk_stop_terminate();
nrf_802154_clock_hfclk_start();
nrf_raal_continuous_mode_enter();
}
}
mutex_unlock(&m_req_mutex);
}
while (monitor != m_req_mutex_monitor);
}
/** @brief Get currently approved priority level.
*
* @return Maximal priority level approved by all radio preconditions.
*/
static inline rsch_prio_t approved_prio_lvl_get(void)
{
rsch_prio_t result = RSCH_PRIO_MAX;
for (uint32_t i = 0; i < RSCH_PREC_CNT; i++)
{
if (m_approved_prios[i] < result)
{
result = m_approved_prios[i];
}
}
return result;
}
/** @brief Check if all preconditions are requested or met at given priority level or higher.
*
* @param[in] prio Minimal priority level requested from preconditions.
*
* @retval true All preconditions are requested or met at given or higher level.
* @retval false At least one precondition is requested at lower level than required.
*/
static inline bool requested_prio_lvl_is_at_least(rsch_prio_t prio)
{
return m_requested_prio >= prio;
}
/** @brief Notify core if preconditions are approved or denied if current state differs from last reported.
*/
static inline void notify_core(void)
{
rsch_prio_t approved_prio_lvl;
uint8_t temp_mon;
do
{
if (!mutex_trylock(&m_ntf_mutex, &m_ntf_mutex_monitor))
{
return;
}
/* It is possible that preemption is not detected (m_ntf_mutex_monitor is read after
* acquiring mutex). It is not a problem because we will call proper handler function
* requested by preempting context. Avoiding this race would generate one additional
* iteration without any effect.
*/
temp_mon = m_ntf_mutex_monitor;
approved_prio_lvl = approved_prio_lvl_get();
if ((m_cont_mode_prio > RSCH_PRIO_IDLE) && (m_last_notified_prio != approved_prio_lvl))
{
m_last_notified_prio = approved_prio_lvl;
nrf_802154_rsch_continuous_prio_changed(approved_prio_lvl);
}
mutex_unlock(&m_ntf_mutex);
}
while (temp_mon != m_ntf_mutex_monitor);
}
/** Timer callback used to trigger delayed timeslot.
*
* @param[in] p_context Index of the delayed timeslot operation (TX or RX).
*/
static void delayed_timeslot_start(void * p_context)
{
rsch_dly_ts_id_t dly_ts_id = (rsch_dly_ts_id_t)(uint32_t)p_context;
dly_ts_t * p_dly_ts = &m_dly_ts[dly_ts_id];
rsch_prio_t req_prio_lvl;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RSCH_TIMER_DELAYED_START);
req_prio_lvl = p_dly_ts->prio;
p_dly_ts->prio = RSCH_PRIO_IDLE;
if (approved_prio_lvl_get() >= req_prio_lvl)
{
nrf_802154_rsch_delayed_timeslot_started(dly_ts_id);
}
else
{
nrf_802154_rsch_delayed_timeslot_failed(dly_ts_id);
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RSCH_TIMER_DELAYED_START);
}
/** Timer callback used to request preconditions for delayed timeslot.
*
* @param[in] p_context Index of the delayed timeslot operation (TX or RX).
*/
static void delayed_timeslot_prec_request(void * p_context)
{
rsch_dly_ts_id_t dly_ts_id = (rsch_dly_ts_id_t)(uint32_t)p_context;
dly_ts_t * p_dly_ts = &m_dly_ts[dly_ts_id];
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RSCH_TIMER_DELAYED_PREC);
all_prec_update();
p_dly_ts->timer.t0 = p_dly_ts->t0;
p_dly_ts->timer.dt = p_dly_ts->dt;
p_dly_ts->timer.callback = delayed_timeslot_start;
p_dly_ts->timer.p_context = p_context;
nrf_802154_timer_sched_add(&p_dly_ts->timer, true);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RSCH_TIMER_DELAYED_PREC);
}
/***************************************************************************************************
* Public API
**************************************************************************************************/
void nrf_802154_rsch_init(void)
{
nrf_raal_init();
m_ntf_mutex = 0;
m_req_mutex = 0;
m_last_notified_prio = RSCH_PRIO_IDLE;
m_cont_mode_prio = RSCH_PRIO_IDLE;
m_requested_prio = RSCH_PRIO_IDLE;
for (uint32_t i = 0; i < RSCH_DLY_TS_NUM; i++)
{
m_dly_ts[i].prio = RSCH_PRIO_IDLE;
}
for (uint32_t i = 0; i < RSCH_PREC_CNT; i++)
{
m_approved_prios[i] = RSCH_PRIO_IDLE;
}
}
void nrf_802154_rsch_uninit(void)
{
for (uint32_t i = 0; i < RSCH_DLY_TS_NUM; i++)
{
nrf_802154_timer_sched_remove(&m_dly_ts[i].timer);
}
nrf_raal_uninit();
}
void nrf_802154_rsch_continuous_mode_priority_set(rsch_prio_t prio)
{
nrf_802154_log(EVENT_TRACE_ENTER, (prio > RSCH_PRIO_IDLE) ? FUNCTION_RSCH_CONTINUOUS_ENTER :
FUNCTION_RSCH_CONTINUOUS_EXIT);
m_cont_mode_prio = prio;
__DMB();
all_prec_update();
notify_core();
if (prio == RSCH_PRIO_IDLE)
{
m_last_notified_prio = RSCH_PRIO_IDLE;
}
nrf_802154_log(EVENT_TRACE_EXIT, (prio > RSCH_PRIO_IDLE) ? FUNCTION_RSCH_CONTINUOUS_ENTER :
FUNCTION_RSCH_CONTINUOUS_EXIT);
}
void nrf_802154_rsch_continuous_ended(void)
{
nrf_raal_continuous_ended();
}
bool nrf_802154_rsch_timeslot_request(uint32_t length_us)
{
return nrf_raal_timeslot_request(length_us);
}
bool nrf_802154_rsch_delayed_timeslot_request(uint32_t t0,
uint32_t dt,
uint32_t length,
rsch_prio_t prio,
rsch_dly_ts_id_t dly_ts_id)
{
(void)length;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RSCH_DELAYED_TIMESLOT_REQ);
assert(dly_ts_id < RSCH_DLY_TS_NUM);
dly_ts_t * p_dly_ts = &m_dly_ts[dly_ts_id];
uint32_t now = nrf_802154_timer_sched_time_get();
uint32_t req_dt = dt - PREC_RAMP_UP_TIME;
bool result;
assert(!nrf_802154_timer_sched_is_running(&p_dly_ts->timer));
assert(p_dly_ts->prio == RSCH_PRIO_IDLE);
assert(prio != RSCH_PRIO_IDLE);
if (nrf_802154_timer_sched_time_is_in_future(now, t0, req_dt))
{
p_dly_ts->prio = prio;
p_dly_ts->t0 = t0;
p_dly_ts->dt = dt;
p_dly_ts->timer.t0 = t0;
p_dly_ts->timer.dt = req_dt;
p_dly_ts->timer.callback = delayed_timeslot_prec_request;
p_dly_ts->timer.p_context = (void *)dly_ts_id;
nrf_802154_timer_sched_add(&p_dly_ts->timer, false);
result = true;
}
else if (requested_prio_lvl_is_at_least(RSCH_PRIO_MAX) &&
nrf_802154_timer_sched_time_is_in_future(now, t0, dt))
{
p_dly_ts->prio = prio;
p_dly_ts->t0 = t0;
p_dly_ts->dt = dt;
p_dly_ts->timer.t0 = t0;
p_dly_ts->timer.dt = dt;
p_dly_ts->timer.callback = delayed_timeslot_start;
p_dly_ts->timer.p_context = (void *)dly_ts_id;
nrf_802154_timer_sched_add(&p_dly_ts->timer, true);
result = true;
}
else
{
result = false;
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RSCH_DELAYED_TIMESLOT_REQ);
return result;
}
bool nrf_802154_rsch_prec_is_approved(rsch_prec_t prec, rsch_prio_t prio)
{
assert(prec < RSCH_PREC_CNT);
return m_approved_prios[prec] >= prio;
}
uint32_t nrf_802154_rsch_timeslot_us_left_get(void)
{
return nrf_raal_timeslot_us_left_get();
}
// External handlers
void nrf_raal_timeslot_started(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RSCH_TIMESLOT_STARTED);
prec_approved_prio_set(RSCH_PREC_RAAL, RSCH_PRIO_MAX);
notify_core();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RSCH_TIMESLOT_STARTED);
}
void nrf_raal_timeslot_ended(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RSCH_TIMESLOT_ENDED);
prec_approved_prio_set(RSCH_PREC_RAAL, RSCH_PRIO_IDLE);
notify_core();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RSCH_TIMESLOT_ENDED);
}
void nrf_802154_clock_hfclk_ready(void)
{
prec_approved_prio_set(RSCH_PREC_HFCLK, RSCH_PRIO_MAX);
notify_core();
}

View file

@ -1,234 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines Radio Scheduler interface.
*
*/
#ifndef NRF_802154_RSCH_H_
#define NRF_802154_RSCH_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_rsch Radio Scheduler
* @{
* @ingroup nrf_802154
* @brief Radio Scheduler interface.
*
* Radio Scheduler is responsible to schedule in time radio activities and preconditions. It is
* expected that the Radio Scheduler module manages timings to meet requirements requested from the
* core module.
*
* Examples of radio activity preconditions are: High-Frequency Clock running, radio arbiter (RAAL)
* granted access to the RADIO peripheral.
*/
/**
* @brief List of preconditions that have to be met before any radio activity.
*/
typedef enum
{
RSCH_PREC_HFCLK,
RSCH_PREC_RAAL,
RSCH_PREC_CNT,
} rsch_prec_t;
/**
* @brief Priorities of the 802.15.4 radio operations.
*/
typedef enum
{
RSCH_PRIO_IDLE, ///< Priority used in the sleep state. With this priority RSCH releases all preconditions.
RSCH_PRIO_IDLE_LISTENING, ///< Priority used during the idle listening procedure.
RSCH_PRIO_RX, ///< Priority used when a frame is being received.
RSCH_PRIO_DETECT, ///< Priority used to detect channel conditions (CCA, ED).
RSCH_PRIO_TX, ///< Priority used to transmit a frame.
RSCH_PRIO_MIN_APPROVED = RSCH_PRIO_IDLE_LISTENING, ///< Minimal priority indicating that given precondition is approved.
RSCH_PRIO_MAX = RSCH_PRIO_TX, ///< Maximal priority available in the RSCH module.
} rsch_prio_t;
/**
* @brief Enumeration of delayed timeslots ids.
*/
typedef enum
{
RSCH_DLY_TX, ///< Timeslot for delayed tx operation.
RSCH_DLY_RX, ///< Timeslot for delayed rx operation.
RSCH_DLY_TS_NUM, ///< Number of delayed timeslots.
} rsch_dly_ts_id_t;
/**
* @brief Initialize Radio Scheduler.
*
* @note This function shall be called once, before any other function from this module.
*
* Initialize Radio Scheduler.
*
* @note Radio Scheduler starts in inactive mode after initialization. In order to start radio activity
* @ref nrf_802154_rsch_continuous_mode_enter should be called.
*
*/
void nrf_802154_rsch_init(void);
/**
* @brief Uninitialize Radio Scheduler.
*
*/
void nrf_802154_rsch_uninit(void);
/**
* @brief Set priority for the continuous radio mode.
*
* In the continuous mode the radio scheduler should try to satisfy all preconditions as long as
* possible in order to give to the radio driver core as much radio time as possible while
* disturbing the other activities as little as possible.
*
* @note The start of a timeslot will be indicated by @ref nrf_802154_rsch_prec_approved call.
* @note To disable the continuous radio mode, the @ref RSCH_PRIO_IDLE should be used.
*
* @param[in] prio Priority level used in the continuous radio mode.
*
*/
void nrf_802154_rsch_continuous_mode_priority_set(rsch_prio_t prio);
/**
* @brief Confirm that current part of continuous timeslot is ended by the core.
*
* This confirmation is used by the core to synchronize ending of continuous timeslot parts with
* the RSCH module.
*
*/
void nrf_802154_rsch_continuous_ended(void);
/**
* @brief Request timeslot for radio communication immediately.
*
* This function should be called only after @ref nrf_802154_rsch_prec_approved indicated the
* start of a timeslot.
*
* @param[in] length_us Requested radio timeslot length in microsecond.
*
* @retval true The radio driver now has exclusive access to the RADIO peripheral for the
* full length of the timeslot.
* @retval false Slot cannot be assigned due to other activities.
*
*/
bool nrf_802154_rsch_timeslot_request(uint32_t length_us);
/**
* @brief Request timeslot in the future.
*
* Request timeslot that should be granted in the future. Function parameters provides data when
* the timeslot should start and how long should it last. When requested timeslot starts the
* @ref nrf_802154_rsch_delayed_timeslot_started is called. If requested timeslot cannot be granted
* with requested parameters, the @ref nrf_802154_rsch_delayed_timeslot_failed is called.
*
* @note Time parameters use the same units that are used in the Timer Scheduler module.
*
* @param[in] t0 Base time of the timestamp of the timeslot start [us].
* @param[in] dt Time delta between @p t0 and the timestamp of the timeslot start [us].
* @param[in] length Requested radio timeslot length [us].
* @param[in] prio Priority level required for the delayed timeslot.
* @param[in] dly_ts Type of the requested timeslot.
*
* @retval true Requested timeslot has been scheduled.
* @retval false Requested timeslot cannot be scheduled and will not be granted.
*/
bool nrf_802154_rsch_delayed_timeslot_request(uint32_t t0,
uint32_t dt,
uint32_t length,
rsch_prio_t prio,
rsch_dly_ts_id_t dly_ts);
/**
* @brief Check if the RSCH precondition is satisfied.
*
* @param[in] prec RSCH precondition to be checked.
* @param[in] prio Minimal required priority level of given precondition.
*
* @retval true Precondition @p prec is currently granted.
* @retval false Precondition @p prec is not currently granted.
*/
bool nrf_802154_rsch_prec_is_approved(rsch_prec_t prec, rsch_prio_t prio);
/**
* @brief Get left time of currently granted timeslot [us].
*
* @returns Number of microseconds left in currently granted timeslot.
*/
uint32_t nrf_802154_rsch_timeslot_us_left_get(void);
/**
* @brief This function is called to notify the core about changes of approved priority level.
*
* If the @p prio is greater than @ref RSCH_PRIO_IDLE, the radio driver has exclusive access to the
* peripherals until this function is called with the @p prio equal to @ref RSCH_PRIO_IDLE.
*
* @note The end of the timeslot is indicated by @p prio equal to the @ref RSCH_PRIO_IDLE.
*
* @param[in] prio Currently approved priority level.
*/
extern void nrf_802154_rsch_continuous_prio_changed(rsch_prio_t prio);
/**
* @brief Notification that previously requested delayed timeslot has started just now.
*
* @param[in] dly_ts_id Type of the started timeslot.
*/
extern void nrf_802154_rsch_delayed_timeslot_started(rsch_dly_ts_id_t dly_ts_id);
/**
* @brief Notification that previously requested delayed timeslot cannot be started.
*
* This function may be called when any of radio activity precondition is not satisfied at the
* time when the timeslot should start.
*
* @param[in] dly_ts_id Type of the failed timeslot.
*/
extern void nrf_802154_rsch_delayed_timeslot_failed(rsch_dly_ts_id_t dly_ts_id);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_RSCH_H_ */

View file

@ -1,154 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements critical sections for the RSCH module.
*
*/
#include "nrf_802154_rsch_crit_sect.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf_802154_critical_section.h"
#include "nrf_802154_rsch.h"
#include <nrf.h>
#define RSCH_EVT_NONE (rsch_prio_t)UINT8_MAX
static volatile uint8_t m_rsch_pending_evt; ///< Indicator of pending RSCH event.
/***************************************************************************************************
* @section RSCH pending events management
**************************************************************************************************/
static void rsch_pending_evt_set(rsch_prio_t prio)
{
volatile uint8_t rsch_pending_evt; // Dummy variable to prevent compilers from removing ldrex
do
{
rsch_pending_evt = __LDREXB(&m_rsch_pending_evt);
(void)rsch_pending_evt;
}
while (__STREXB((uint8_t)prio, &m_rsch_pending_evt));
}
static rsch_prio_t rsch_pending_evt_clear(void)
{
uint8_t evt_value;
do
{
evt_value = __LDREXB(&m_rsch_pending_evt);
}
while (__STREXB(RSCH_EVT_NONE, &m_rsch_pending_evt));
return (rsch_prio_t)evt_value;
}
static bool rsch_pending_evt_is_none(void)
{
return m_rsch_pending_evt == (uint8_t)RSCH_EVT_NONE;
}
static void rsch_evt_process(rsch_prio_t evt)
{
if (evt != RSCH_EVT_NONE)
{
nrf_802154_rsch_crit_sect_prio_changed(evt);
}
}
/***************************************************************************************************
* @section Public API
**************************************************************************************************/
void nrf_802154_rsch_crit_sect_init(void)
{
m_rsch_pending_evt = RSCH_EVT_NONE;
}
void nrf_802154_rsch_crit_sect_prio_request(rsch_prio_t prio)
{
nrf_802154_rsch_continuous_mode_priority_set(prio);
}
/***************************************************************************************************
* @section RSCH callbacks
**************************************************************************************************/
void nrf_802154_rsch_continuous_prio_changed(rsch_prio_t prio)
{
bool crit_sect_success = false;
crit_sect_success = nrf_802154_critical_section_enter();
// If we managed to enter critical section, but there is already a pending event,
// it means that the Critical Section module is about to make one more iteration of the
// critical section exit procedure. To prevent race in continuous mode priorities notification,
// we do not notify directly, but just update the pending event.
if (crit_sect_success && rsch_pending_evt_is_none())
{
nrf_802154_rsch_crit_sect_prio_changed(prio);
}
else
{
rsch_pending_evt_set(prio);
}
if (crit_sect_success)
{
nrf_802154_critical_section_exit();
}
}
/***************************************************************************************************
* @section Critical section callbacks
**************************************************************************************************/
void nrf_802154_critical_section_rsch_enter(void)
{
// Intentionally empty
}
void nrf_802154_critical_section_rsch_exit(void)
{
rsch_evt_process(rsch_pending_evt_clear());
}
bool nrf_802154_critical_section_rsch_event_is_pending(void)
{
return !rsch_pending_evt_is_none();
}

View file

@ -1,71 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_802154_RSCH_CRIT_SECT_H__
#define NRF_802154_RSCH_CRIT_SECT_H__
#include <stdbool.h>
#include "nrf_802154_rsch.h"
/**
* @defgroup nrf_802154_rsch_crit_sect RSCH event queue used during critical sections
* @{
* @ingroup nrf_802154_rsch
* @brief Critical section implementation for the RSCH module.
*/
/**
* @brief Initialize the RSCH critical section module.
*/
void nrf_802154_rsch_crit_sect_init(void);
/**
* @brief Request priority level from RSCH through the critical section module.
*
* @param[in] prio Requested priority level.
*/
void nrf_802154_rsch_crit_sect_prio_request(rsch_prio_t prio);
/**
* @brief This function is called to notify the core that approved RSCH priority has changed.
*
* @note This function is called from critical section context and does not preempt other critical
* sections.
*
* @param[in] prio Approved priority level.
*/
extern void nrf_802154_rsch_crit_sect_prio_changed(rsch_prio_t prio);
/**
*@}
**/
#endif // NRF_802154_RSCH_CRIT_SECT_H__

View file

@ -1,108 +0,0 @@
/* Copyright (c) 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines the Wifi coexistence module.
*
*/
#ifndef NRF_802154_WIFI_COEX_H_
#define NRF_802154_WIFI_COEX_H_
#include "nrf_802154_rsch.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_wifi_coex Wifi Coexistence
* @{
* @ingroup nrf_802154
* @brief Wifi Coexistence module.
*
* Wifi Coexistence module is a client of the PTA (defined in the 802.15.2). It manages GPIO
* to assert pins and respond to pin state changes.
*/
/**
* @brief Initialize the Wifi Coexistence module.
*
* @note This function shall be called once, before any other function from this module.
*
*/
void nrf_802154_wifi_coex_init(void);
/**
* @brief Uninitialize the Wifi Coexistence module.
*
*/
void nrf_802154_wifi_coex_uninit(void);
/**
* @brief Request given priority from the Wifi Coexistence module.
*
* @note The approval of requested priority is notified asynchronously by the
* @ref nrf_802154_wifi_coex_prio_changed call.
*
* @param[in] priority Requested priority level.
*
*/
void nrf_802154_wifi_coex_prio_req(rsch_prio_t priority);
/**
* @brief Get priority denial event address.
*
* Get an address of a hardware event that notifies about denial of the previously approved
* priority.
*
* @return Address of a priority denial event.
*/
void * nrf_802154_wifi_coex_deny_event_addr_get(void);
/**
* @biref Approved priority change notification.
*
* The Wifi Coexistence module calls this function to notify the RSCH of currently approved
* priority level.
*
* @param[in] priority Approved priority level.
*/
extern void nrf_802154_wifi_coex_prio_changed(rsch_prio_t priority);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_WIFI_COEX_H_ */

View file

@ -1,190 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines Radio Arbiter Abstraction Layer interface.
*
*/
#ifndef NRF_RAAL_API_H_
#define NRF_RAAL_API_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_raal Radio Arbiter Abstraction Layer
* @{
* @ingroup nrf_802154
* @brief Radio Arbiter Abstraction Layer interface.
*/
/**
* @brief Initialize RAAL.
*
* @note This function shall be called once, before any other function from this module.
*
* Initialize Radio Arbiter Abstraction Layer client.
*
* @note Arbiter starts in inactive mode after initialization. In order to start radio activity
* @p nrf_raal_continuous_mode_enter method should be called.
*
*/
void nrf_raal_init(void);
/**
* @brief Uninitialize RAAL.
*
* Uninitialize Radio Arbiter Abstraction Layer client.
*
*/
void nrf_raal_uninit(void);
/**
* @brief Enter arbiter into continuous radio mode.
*
* In this mode radio arbiter should try to create long continuous timeslots that will give the
* radio driver as much radio time as possible while disturbing the other activities as little
* as possible.
* The arbiter client shall make sure that high frequency clock is enabled in each timeslot.
*
* @note The start of a timeslot will be indicated by @p nrf_raal_timeslot_started call.
*
*/
void nrf_raal_continuous_mode_enter(void);
/**
* @brief Exit arbiter from continuous mode.
*
* In this mode radio arbiter will not extend or allocate any more timeslots for radio driver.
*
*/
void nrf_raal_continuous_mode_exit(void);
/**
* @brief Confirm to RAAL that current part of the continuous timeslot is ended.
*
* The core cannot use the RADIO peripheral after this call until the timeslot is started again.
*/
void nrf_raal_continuous_ended(void);
/**
* @brief Request timeslot for radio communication.
*
* This method should be called only after @p nrf_raal_timeslot_started indicated the start
* of a timeslot.
*
* @param[in] length_us Requested radio timeslot length in microsecond.
*
* @retval TRUE The radio driver now has exclusive access to the RADIO peripheral for the
* full length of the timeslot.
* @retval FALSE Slot cannot be assigned due to other activities.
*
*/
bool nrf_raal_timeslot_request(uint32_t length_us);
/**
* @brief Get left time of currently granted timeslot [us].
*
* @returns Number of microseconds left in currently granted timeslot.
*/
uint32_t nrf_raal_timeslot_us_left_get(void);
/**
* @brief Enter critical section of the module.
*
* When this method is called, the execution of the @sa nrf_raal_timeslot_started and
* @sa nrf_raal_timeslot_ended function is blocked.
*
* @note This function may be called when RAAL is already in critical section. Ongoing call may
* be interrupted by another call from IRQ with higher priority.
*
*/
void nrf_raal_critical_section_enter(void);
/**
* @brief Exit critical section of the module.
*
* When this method is called driver has to expect the execution of the
* @sa nrf_raal_timeslot_started or @sa nrf_raal_timeslot_ended
* function.
*
* @note This function may be called when RAAL has already exited critical section. Ongoing call
* may NOT be interrupted by another call from IRQ with higher priority.
*/
void nrf_raal_critical_section_exit(void);
/**
* @brief RAAL client calls this method to notify radio driver about the start of a timeslot.
*
* The radio driver now has exclusive access to the peripherals until @p nrf_raal_timeslot_ended
* is called.
*
* @note The high frequency clock must be enabled when this function is called.
* @note The end of the timeslot will be indicated by @p nrf_raal_timeslot_ended function.
*
*/
extern void nrf_raal_timeslot_started(void);
/**
* @brief RAAL client calls this method to notify radio driver about the end of a timeslot.
*
* Depending on the RAAL client configuration, radio driver has NRF_RAAL_MAX_CLEAN_UP_TIME_US
* microseconds to do any clean-up actions on RADIO peripheral and stop using it completely.
* Thus arbiter has to call this function NRF_RAAL_MAX_CLEAN_UP_TIME_US microseconds before
* timeslot is finished.
*
* If RAAL is in the continuous mode, the next timeslot will be indicated again by
* @p nrf_raal_timeslot_started function.
*
* This method shall not be called if @p nrf_raal_continuous_mode_exit has been called. Radio
* driver shall assume that timeslot has been finished after @p nrf_raal_continuous_mode_exit
* call.
*
* @note Because radio driver needs to stop any operation on RADIO peripheral within
* NRF_RAAL_MAX_CLEAN_UP_TIME_US microseconds, this method should be called with high
* interrupt priority level to avoid unwanted delays.
*
*/
extern void nrf_raal_timeslot_ended(void);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_RAAL_API_H_ */

View file

@ -1,70 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef NRF_RAAL_CONFIG_H__
#define NRF_RAAL_CONFIG_H__
#ifdef NRF_802154_PROJECT_CONFIG
#include NRF_802154_PROJECT_CONFIG
#endif
#include <nrf.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_raal_config RAAL configuration
* @{
* @ingroup nrf_802154
* @brief Configuration of Radio Arbiter Abstraction Layer.
*/
/**
* @def NRF_RAAL_MAX_CLEAN_UP_TIME_US
*
* Maximum time within radio driver needs to do any clean-up actions on RADIO peripheral
* and stop using it completely.
*
*/
#ifndef NRF_RAAL_MAX_CLEAN_UP_TIME_US
#define NRF_RAAL_MAX_CLEAN_UP_TIME_US 91
#endif
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif // NRF_RAAL_CONFIG_H__

View file

@ -1,251 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 simulated radio arbiter.
*
* This arbiter should be used for testing driver and tweaking other arbiters.
*
*/
#include "nrf_raal_api.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include "nrf.h"
#include "nrf_802154_debug.h"
static bool m_continuous_requested;
static bool m_continuous_granted;
static uint16_t m_time_interval = 250; // ms
static uint16_t m_ble_duty = 10; // ms
static uint16_t m_pre_preemption_notification = 150; // us
static uint32_t m_ended_timestamp;
static uint32_t m_started_timestamp;
static uint32_t m_margin_timestamp;
static void continuous_grant(void)
{
if (m_continuous_requested && !m_continuous_granted)
{
nrf_802154_pin_set(PIN_DBG_TIMESLOT_ACTIVE);
m_continuous_granted = true;
nrf_raal_timeslot_started();
}
}
static void continuous_revoke(void)
{
if (m_continuous_requested && m_continuous_granted)
{
nrf_802154_pin_clr(PIN_DBG_TIMESLOT_ACTIVE);
m_continuous_granted = false;
nrf_raal_timeslot_ended();
}
}
static uint32_t time_get(void)
{
NRF_TIMER0->TASKS_CAPTURE[1] = 1;
return NRF_TIMER0->CC[1];
}
void nrf_raal_init(void)
{
m_ended_timestamp = m_time_interval * 1000UL;
m_started_timestamp = m_ble_duty * 1000UL;
m_margin_timestamp = (m_time_interval * 1000UL) - m_pre_preemption_notification;
NRF_MWU->PREGION[0].SUBS = 0x00000002;
NRF_MWU->INTENSET = MWU_INTENSET_PREGION0WA_Msk | MWU_INTENSET_PREGION0RA_Msk;
NVIC_SetPriority(MWU_IRQn, 0);
NVIC_ClearPendingIRQ(MWU_IRQn);
NVIC_EnableIRQ(MWU_IRQn);
NRF_TIMER0->MODE = TIMER_MODE_MODE_Timer;
NRF_TIMER0->BITMODE = TIMER_BITMODE_BITMODE_24Bit;
NRF_TIMER0->PRESCALER = 4;
NRF_TIMER0->INTENSET = TIMER_INTENSET_COMPARE0_Msk;
NRF_TIMER0->CC[0] = m_started_timestamp;
NVIC_SetPriority(TIMER0_IRQn, 1);
NVIC_ClearPendingIRQ(TIMER0_IRQn);
NVIC_EnableIRQ(TIMER0_IRQn);
m_continuous_requested = false;
NRF_TIMER0->TASKS_START = 1;
}
void nrf_raal_uninit(void)
{
// Intentionally empty.
}
void nrf_raal_continuous_mode_enter(void)
{
uint32_t time;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_CONTINUOUS_ENTER);
assert(!m_continuous_requested);
m_continuous_requested = true;
NVIC_DisableIRQ(TIMER0_IRQn);
__DSB();
__ISB();
time = time_get();
if ((time >= m_started_timestamp) && (time < m_margin_timestamp))
{
continuous_grant();
}
NVIC_EnableIRQ(TIMER0_IRQn);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_CONTINUOUS_ENTER);
}
void nrf_raal_continuous_mode_exit(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_CONTINUOUS_EXIT);
assert(m_continuous_requested);
m_continuous_requested = false;
m_continuous_granted = false;
nrf_802154_pin_clr(PIN_DBG_TIMESLOT_ACTIVE);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_CONTINUOUS_EXIT);
}
void nrf_raal_continuous_ended(void)
{
// Intentionally empty.
}
bool nrf_raal_timeslot_request(uint32_t length_us)
{
uint32_t timer;
assert(m_continuous_requested);
if (!m_continuous_granted)
{
return false;
}
timer = time_get();
return (timer >= m_started_timestamp) && ((timer + length_us) < m_margin_timestamp);
}
uint32_t nrf_raal_timeslot_us_left_get(void)
{
uint32_t timer = time_get();
return ((timer >= m_started_timestamp) && (timer < m_margin_timestamp)) ?
(m_margin_timestamp - timer) : 0;
}
void TIMER0_IRQHandler(void)
{
uint32_t ev_timestamp;
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_HANDLER);
if (NRF_TIMER0->EVENTS_COMPARE[0])
{
while (time_get() >= NRF_TIMER0->CC[0])
{
NRF_TIMER0->EVENTS_COMPARE[0] = 0;
ev_timestamp = NRF_TIMER0->CC[0];
if (ev_timestamp == m_ended_timestamp)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_ENDED);
NRF_MWU->REGIONENSET = MWU_REGIONENSET_PRGN0WA_Msk | MWU_REGIONENSET_PRGN0RA_Msk;
NRF_TIMER0->TASKS_STOP = 1;
NRF_TIMER0->TASKS_CLEAR = 1;
NRF_TIMER0->CC[0] = m_started_timestamp;
NRF_TIMER0->TASKS_START = 1;
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_ENDED);
}
else if (ev_timestamp == m_started_timestamp)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_START);
NRF_MWU->REGIONENCLR = MWU_REGIONENCLR_PRGN0WA_Msk | MWU_REGIONENCLR_PRGN0RA_Msk;
NRF_TIMER0->CC[0] = m_margin_timestamp;
continuous_grant();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_START);
}
else if (ev_timestamp == m_margin_timestamp)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_MARGIN);
NRF_TIMER0->CC[0] = m_ended_timestamp;
continuous_revoke();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_MARGIN);
}
else
{
assert(false);
}
}
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_HANDLER);
}
void MWU_IRQHandler(void)
{
assert(false);
}

View file

@ -1,89 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 radio arbiter for single phy.
*
* This arbiter should be used when 802.15.4 is the only wireless protocol used by the application.
*
*/
#include "nrf_raal_api.h"
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
static bool m_continuous;
void nrf_raal_init(void)
{
m_continuous = false;
}
void nrf_raal_uninit(void)
{
// Intentionally empty.
}
void nrf_raal_continuous_mode_enter(void)
{
assert(!m_continuous);
m_continuous = true;
nrf_raal_timeslot_started();
}
void nrf_raal_continuous_mode_exit(void)
{
assert(m_continuous);
m_continuous = false;
}
void nrf_raal_continuous_ended(void)
{
// Intentionally empty.
}
bool nrf_raal_timeslot_request(uint32_t length_us)
{
(void)length_us;
assert(m_continuous);
return true;
}
uint32_t nrf_raal_timeslot_us_left_get(void)
{
return UINT32_MAX;
}

View file

@ -1,796 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements the nrf 802.15.4 radio arbiter for softdevice.
*
* This arbiter should be used when 802.15.4 works concurrently with SoftDevice's radio stack.
*
*/
#include "nrf_raal_softdevice.h"
#include <assert.h>
#include <stdbool.h>
#include <string.h>
#include <hal/nrf_timer.h>
#include <nrf_raal_api.h>
#include <nrf_802154.h>
#include <nrf_802154_const.h>
#include <nrf_802154_debug.h>
#include <nrf_802154_procedures_duration.h>
#include <nrf_802154_utils.h>
#if defined(__GNUC__)
_Pragma("GCC diagnostic push")
_Pragma("GCC diagnostic ignored \"-Wreturn-type\"")
_Pragma("GCC diagnostic ignored \"-Wunused-parameter\"")
_Pragma("GCC diagnostic ignored \"-Wpedantic\"")
#endif
#include <ble.h>
#include <nrf_mbr.h>
#include <nrf_sdm.h>
#include <nrf_soc.h>
#if defined(__GNUC__)
_Pragma("GCC diagnostic pop")
#endif
/***************************************************************************************************
* @section Defines and typedefs.
**************************************************************************************************/
/*
* @brief Defines the minimum version of the SoftDevice that supports configuration of BLE advertising
* role scheduling.
*
* The first SoftDevice that supports this option is S140 6.1.1 (6001001). The full version
* number for the SoftDevice binary is a decimal number in the form Mmmmbbb, where:
* - M is major version (one or more digits)
* - mmm is minor version (three digits)
* - bbb is bugfix version (three digits).
*/
#define BLE_ADV_SCHED_CFG_SUPPORT_MIN_SD_VERSION (6001001)
/**@brief Enable Request and End on timeslot safety interrupt. */
#define ENABLE_REQUEST_AND_END_ON_TIMESLOT_END 0
/**@brief RAAL Timer instance. */
#define RAAL_TIMER NRF_TIMER0
/**@brief RAAL Timer interrupt number. */
#define RAAL_TIMER_IRQn TIMER0_IRQn
/**@brief Minimum time prior safe margin reached by RTC when TIMER reports reached margin in microseconds. */
#define MIN_TIME_PRIOR_MARGIN_IS_REACHED_US 31
/**@brief Timer compare channel definitions. */
#define TIMER_CC_ACTION NRF_TIMER_CC_CHANNEL0
#define TIMER_CC_ACTION_EVENT NRF_TIMER_EVENT_COMPARE0
#define TIMER_CC_ACTION_INT NRF_TIMER_INT_COMPARE0_MASK
#define TIMER_CC_CAPTURE NRF_TIMER_CC_CHANNEL1
#define TIMER_CC_CAPTURE_TASK NRF_TIMER_TASK_CAPTURE1
#define MINIMUM_TIMESLOT_LENGTH_EXTENSION_TIME_TICKS NRF_802154_US_TO_RTC_TICKS( \
NRF_RADIO_MINIMUM_TIMESLOT_LENGTH_EXTENSION_TIME_US)
/**@brief PPM constants. */
#define PPM_UNIT 1000000UL
#define MAX_HFCLK_PPM 40
/**@brief Defines states of timeslot. */
typedef enum
{
TIMESLOT_STATE_IDLE = 0,
TIMESLOT_STATE_REQUESTED,
TIMESLOT_STATE_GRANTED
} timeslot_state_t;
/**@brief Define timer actions. */
typedef enum
{
TIMER_ACTION_EXTEND,
TIMER_ACTION_MARGIN,
} timer_action_t;
/***************************************************************************************************
* @section Static variables.
**************************************************************************************************/
/**@brief Defines if module has been initialized. */
static bool m_initialized = false;
/**@brief Request parameters. */
static nrf_radio_request_t m_request;
/**@brief Return parameter for SD radio signal handler. */
static nrf_radio_signal_callback_return_param_t m_ret_param;
/**@brief Current configuration of the RAAL. */
static nrf_raal_softdevice_cfg_t m_config;
/**@brief Defines if RAAL is in continuous mode. */
static volatile bool m_continuous = false;
/**@brief Defines if RAAL is currently in a timeslot. */
static volatile timeslot_state_t m_timeslot_state;
/**@brief Current action of the timer. */
static timer_action_t m_timer_action;
/**@brief Current timeslot length. */
static uint16_t m_timeslot_length;
/**@brief Previously granted timeslot length. */
static uint16_t m_prev_timeslot_length;
/**@brief Interval between successive timeslot extensions. */
static uint16_t m_extension_interval;
/**@brief Number of already performed extentions tries on failed event. */
static volatile uint16_t m_timeslot_extend_tries;
/***************************************************************************************************
* @section Drift calculations
**************************************************************************************************/
static uint32_t time_corrected_for_drift_get(uint32_t time)
{
uint32_t ppm = m_config.lf_clk_accuracy_ppm + MAX_HFCLK_PPM;
return time - NRF_802154_DIVIDE_AND_CEIL(time * ppm, PPM_UNIT);
}
static void calculate_config(void)
{
m_extension_interval = time_corrected_for_drift_get(m_config.timeslot_length);
}
/***************************************************************************************************
* @section Operations on RAAL TIMER.
**************************************************************************************************/
/**@brief Set timer on timeslot started. */
static void timer_start(void)
{
m_timer_action = TIMER_ACTION_EXTEND;
nrf_timer_task_trigger(RAAL_TIMER, NRF_TIMER_TASK_STOP);
nrf_timer_task_trigger(RAAL_TIMER, NRF_TIMER_TASK_CLEAR);
nrf_timer_bit_width_set(RAAL_TIMER, NRF_TIMER_BIT_WIDTH_32);
nrf_timer_cc_write(RAAL_TIMER, TIMER_CC_ACTION, 0);
nrf_timer_task_trigger(RAAL_TIMER, NRF_TIMER_TASK_START);
NVIC_EnableIRQ(RAAL_TIMER_IRQn);
}
/**@brief Reset timer. */
static void timer_reset(void)
{
nrf_timer_task_trigger(RAAL_TIMER, NRF_TIMER_TASK_STOP);
nrf_timer_event_clear(RAAL_TIMER, TIMER_CC_ACTION_EVENT);
NVIC_ClearPendingIRQ(RAAL_TIMER_IRQn);
}
/**@brief Get current time on RAAL Timer. */
static inline uint32_t timer_time_get(void)
{
nrf_timer_task_trigger(RAAL_TIMER, TIMER_CC_CAPTURE_TASK);
return nrf_timer_cc_read(RAAL_TIMER, TIMER_CC_CAPTURE);
}
/**@brief Check if timer is set to margin.
*
* @retval true Timer action CC is set to the margin action.
* @retval false Timer action CC is set to the extend action.
*/
static inline bool timer_is_set_to_margin(void)
{
return m_timer_action == TIMER_ACTION_MARGIN;
}
static inline uint32_t ticks_to_timeslot_end_get(void)
{
uint32_t cc = NRF_RTC0->CC[1];
uint32_t counter = NRF_RTC0->COUNTER;
// We add one tick as RTC might be just about to increment COUNTER value.
return (cc - (counter + 1)) & RTC_COUNTER_COUNTER_Msk;
}
static inline uint32_t safe_time_to_timeslot_end_get(void)
{
uint32_t margin = m_config.timeslot_safe_margin + NRF_RADIO_START_JITTER_US;
uint32_t timeslot_end = NRF_802154_RTC_TICKS_TO_US(ticks_to_timeslot_end_get());
if (timeslot_end > margin)
{
return timeslot_end - margin;
}
else
{
return 0;
}
}
/**@brief Get timeslot margin. */
static uint32_t timer_get_cc_margin(void)
{
uint32_t corrected_time_to_margin = time_corrected_for_drift_get(
safe_time_to_timeslot_end_get());
return timer_time_get() + corrected_time_to_margin;
}
/**@brief Set timer action to the timeslot margin. */
static inline void timer_to_margin_set(void)
{
uint32_t margin_cc = timer_get_cc_margin();
m_timer_action = TIMER_ACTION_MARGIN;
nrf_timer_event_clear(RAAL_TIMER, TIMER_CC_ACTION_EVENT);
nrf_timer_cc_write(RAAL_TIMER, TIMER_CC_ACTION, margin_cc);
nrf_timer_int_enable(RAAL_TIMER, TIMER_CC_ACTION_INT);
}
/**@brief Check if margin is already reached. */
static inline bool timer_is_margin_reached(void)
{
return timer_is_set_to_margin() && nrf_timer_event_check(RAAL_TIMER, TIMER_CC_ACTION_EVENT) &&
safe_time_to_timeslot_end_get() <= MIN_TIME_PRIOR_MARGIN_IS_REACHED_US;
}
/**@brief Set timer on extend event. */
static void timer_on_extend_update(void)
{
NVIC_ClearPendingIRQ(RAAL_TIMER_IRQn);
if (timer_is_set_to_margin())
{
uint32_t margin_cc = nrf_timer_cc_read(RAAL_TIMER, TIMER_CC_ACTION);
margin_cc += m_timeslot_length;
nrf_timer_cc_write(RAAL_TIMER, TIMER_CC_ACTION, margin_cc);
}
else
{
uint16_t extension_interval = (m_prev_timeslot_length == m_config.timeslot_length) ?
m_extension_interval :
time_corrected_for_drift_get(m_prev_timeslot_length);
nrf_timer_cc_write(RAAL_TIMER, TIMER_CC_ACTION,
nrf_timer_cc_read(RAAL_TIMER, TIMER_CC_ACTION) + extension_interval);
nrf_timer_int_enable(RAAL_TIMER, TIMER_CC_ACTION_INT);
}
}
/***************************************************************************************************
* @section Timeslot related functions.
**************************************************************************************************/
/**@brief Initialize timeslot internal variables. */
static inline void timeslot_data_init(void)
{
m_timeslot_extend_tries = 0;
m_timeslot_length = m_config.timeslot_length;
}
/**@brief Indicate if timeslot is in idle state. */
static inline bool timeslot_is_idle(void)
{
return (m_timeslot_state == TIMESLOT_STATE_IDLE);
}
/**@brief Indicate if timeslot has been granted. */
static inline bool timeslot_is_granted(void)
{
return (m_timeslot_state == TIMESLOT_STATE_GRANTED);
}
/**@brief Notify driver that timeslot has been started. */
static inline void timeslot_started_notify(void)
{
if (timeslot_is_granted() && m_continuous)
{
nrf_raal_timeslot_started();
}
}
/**@brief Notify driver that timeslot has been ended. */
static inline void timeslot_ended_notify(void)
{
if (!timeslot_is_granted() && m_continuous)
{
nrf_raal_timeslot_ended();
}
}
/**@brief Prepare earliest timeslot request. */
static void timeslot_request_prepare(void)
{
memset(&m_request, 0, sizeof(m_request));
m_request.request_type = NRF_RADIO_REQ_TYPE_EARLIEST;
m_request.params.earliest.hfclk = NRF_RADIO_HFCLK_CFG_NO_GUARANTEE;
m_request.params.earliest.priority = NRF_RADIO_PRIORITY_NORMAL;
m_request.params.earliest.length_us = m_timeslot_length;
m_request.params.earliest.timeout_us = m_config.timeslot_timeout;
}
/**@brief Request earliest timeslot. */
static void timeslot_request(void)
{
timeslot_request_prepare();
m_timeslot_state = TIMESLOT_STATE_REQUESTED;
// Request timeslot from SoftDevice.
uint32_t err_code = sd_radio_request(&m_request);
if (err_code != NRF_SUCCESS)
{
m_timeslot_state = TIMESLOT_STATE_IDLE;
}
nrf_802154_log(EVENT_TIMESLOT_REQUEST, m_request.params.earliest.length_us);
nrf_802154_log(EVENT_TIMESLOT_REQUEST_RESULT, err_code);
}
/**@brief Decrease timeslot length. */
static void timeslot_length_decrease(void)
{
m_timeslot_extend_tries++;
m_timeslot_length = m_timeslot_length >> 1;
}
/**@brief Fill timeslot parameters with extend action. */
static void timeslot_extend(uint32_t timeslot_length)
{
m_ret_param.callback_action = NRF_RADIO_SIGNAL_CALLBACK_ACTION_EXTEND;
m_ret_param.params.extend.length_us = timeslot_length;
nrf_802154_pin_set(PIN_DBG_TIMESLOT_EXTEND_REQ);
nrf_802154_log(EVENT_TIMESLOT_REQUEST, m_ret_param.params.extend.length_us);
}
/**@brief Extend timeslot further. */
static void timeslot_next_extend(void)
{
// Check if we can make another extend query.
if (m_timeslot_extend_tries < m_config.timeslot_alloc_iters)
{
// Decrease timeslot length.
timeslot_length_decrease();
// Try to extend right after start.
timeslot_extend(m_timeslot_length);
}
}
/***************************************************************************************************
* @section RAAL TIMER interrupt handler.
**************************************************************************************************/
/**@brief Handle timer interrupts. */
static void timer_irq_handle(void)
{
// Margin or extend event triggered.
if (nrf_timer_event_check(RAAL_TIMER, TIMER_CC_ACTION_EVENT))
{
if (timer_is_set_to_margin())
{
if (timer_is_margin_reached())
{
// Safe margin exceeded.
nrf_802154_pin_clr(PIN_DBG_TIMESLOT_ACTIVE);
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_MARGIN);
m_timeslot_state = TIMESLOT_STATE_IDLE;
timeslot_ended_notify();
// Ignore any other events.
timer_reset();
// Return and wait for NRF_EVT_RADIO_SESSION_IDLE event.
m_ret_param.callback_action = NRF_RADIO_SIGNAL_CALLBACK_ACTION_NONE;
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_MARGIN);
}
else
{
// Move safety margin a little further to suppress clocks drift
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_MARGIN_MOVE);
timer_to_margin_set();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_MARGIN_MOVE);
}
}
else
{
// Extension margin exceeded.
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_EXTEND);
nrf_timer_int_disable(RAAL_TIMER, TIMER_CC_ACTION_INT);
nrf_timer_event_clear(RAAL_TIMER, TIMER_CC_ACTION_EVENT);
if (m_continuous &&
(nrf_timer_cc_read(RAAL_TIMER, TIMER_CC_ACTION) +
m_config.timeslot_length < m_config.timeslot_max_length))
{
// Try to extend timeslot.
timeslot_extend(m_config.timeslot_length);
}
else
{
// We have reached maximum timeslot length.
timer_to_margin_set();
m_ret_param.callback_action = NRF_RADIO_SIGNAL_CALLBACK_ACTION_NONE;
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_EXTEND);
}
}
else
{
// Should not happen.
assert(false);
}
}
/***************************************************************************************************
* @section SoftDevice signal and SoC handlers.
**************************************************************************************************/
/**@brief Signal handler. */
static nrf_radio_signal_callback_return_param_t * signal_handler(uint8_t signal_type)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_HANDLER);
// Default response.
m_ret_param.callback_action = NRF_RADIO_SIGNAL_CALLBACK_ACTION_NONE;
if (!m_continuous)
{
nrf_802154_pin_clr(PIN_DBG_TIMESLOT_ACTIVE);
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_ENDED);
m_timeslot_state = TIMESLOT_STATE_IDLE;
// TODO: Change to NRF_RADIO_SIGNAL_CALLBACK_ACTION_END (KRKNWK-937)
m_ret_param.callback_action = NRF_RADIO_SIGNAL_CALLBACK_ACTION_NONE;
timer_reset();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_ENDED);
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_HANDLER);
return &m_ret_param;
}
switch (signal_type)
{
case NRF_RADIO_CALLBACK_SIGNAL_TYPE_START: /**< This signal indicates the start of the radio timeslot. */
{
nrf_802154_pin_set(PIN_DBG_TIMESLOT_ACTIVE);
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_START);
assert(m_timeslot_state == TIMESLOT_STATE_REQUESTED);
// Set up timer first with requested timeslot length.
timer_start();
// Re-initialize timeslot data for future extensions.
m_prev_timeslot_length = m_timeslot_length;
timeslot_data_init();
// Try to extend right after start.
timeslot_extend(m_timeslot_length);
// Do not notify started timeslot here. Notify after successful extend to make sure
// enough timeslot length is available before notification.
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_START);
break;
}
case NRF_RADIO_CALLBACK_SIGNAL_TYPE_TIMER0: /**< This signal indicates the TIMER0 interrupt. */
timer_irq_handle();
break;
case NRF_RADIO_CALLBACK_SIGNAL_TYPE_RADIO: /**< This signal indicates the NRF_RADIO interrupt. */
nrf_802154_pin_set(PIN_DBG_TIMESLOT_RADIO_IRQ);
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_RADIO);
if (timeslot_is_granted())
{
if (!timer_is_margin_reached())
{
nrf_802154_radio_irq_handler();
}
else
{
// Handle margin exceeded event.
timer_irq_handle();
}
}
else
{
NVIC_DisableIRQ(RADIO_IRQn);
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_RADIO);
nrf_802154_pin_clr(PIN_DBG_TIMESLOT_RADIO_IRQ);
break;
case NRF_RADIO_CALLBACK_SIGNAL_TYPE_EXTEND_FAILED: /**< This signal indicates extend action failed. */
nrf_802154_pin_tgl(PIN_DBG_TIMESLOT_FAILED);
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_EXTEND_FAIL);
if (!timer_is_set_to_margin())
{
timer_to_margin_set();
}
timeslot_next_extend();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_EXTEND_FAIL);
break;
case NRF_RADIO_CALLBACK_SIGNAL_TYPE_EXTEND_SUCCEEDED: /**< This signal indicates extend action succeeded. */
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_SIG_EVENT_EXTEND_SUCCESS);
if ((!timer_is_set_to_margin()) &&
(ticks_to_timeslot_end_get() <
MINIMUM_TIMESLOT_LENGTH_EXTENSION_TIME_TICKS))
{
timer_to_margin_set();
m_ret_param.callback_action = NRF_RADIO_SIGNAL_CALLBACK_ACTION_NONE;
}
else
{
timer_on_extend_update();
m_prev_timeslot_length = m_timeslot_length;
// Request further extension only if any of previous one failed.
if (m_timeslot_extend_tries != 0)
{
timeslot_next_extend();
}
}
if (!timeslot_is_granted())
{
m_timeslot_state = TIMESLOT_STATE_GRANTED;
timeslot_started_notify();
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_EVENT_EXTEND_SUCCESS);
break;
default:
break;
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_SIG_HANDLER);
return &m_ret_param;
}
void nrf_raal_softdevice_soc_evt_handler(uint32_t evt_id)
{
switch (evt_id)
{
case NRF_EVT_RADIO_BLOCKED:
case NRF_EVT_RADIO_CANCELED:
{
nrf_802154_pin_tgl(PIN_DBG_TIMESLOT_BLOCKED);
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_EVT_BLOCKED);
assert(!timeslot_is_granted());
m_timeslot_state = TIMESLOT_STATE_IDLE;
if (m_continuous)
{
if (m_timeslot_extend_tries < m_config.timeslot_alloc_iters)
{
timeslot_length_decrease();
}
timeslot_request();
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_EVT_BLOCKED);
break;
}
case NRF_EVT_RADIO_SIGNAL_CALLBACK_INVALID_RETURN:
assert(false);
break;
case NRF_EVT_RADIO_SESSION_IDLE:
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_EVT_SESSION_IDLE);
nrf_802154_pin_tgl(PIN_DBG_TIMESLOT_SESSION_IDLE);
if (m_continuous && timeslot_is_idle())
{
timeslot_data_init();
timeslot_request();
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_EVT_SESSION_IDLE);
break;
case NRF_EVT_RADIO_SESSION_CLOSED:
break;
default:
break;
}
}
/***************************************************************************************************
* @section RAAL API.
**************************************************************************************************/
void nrf_raal_softdevice_config(const nrf_raal_softdevice_cfg_t * p_cfg)
{
assert(m_initialized);
assert(!m_continuous);
assert(p_cfg);
m_config = *p_cfg;
calculate_config();
}
void nrf_raal_init(void)
{
assert(!m_initialized);
m_continuous = false;
m_timeslot_state = TIMESLOT_STATE_IDLE;
m_config.timeslot_length = NRF_RAAL_TIMESLOT_DEFAULT_LENGTH;
m_config.timeslot_alloc_iters = NRF_RAAL_TIMESLOT_DEFAULT_ALLOC_ITERS;
m_config.timeslot_safe_margin = NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN;
m_config.timeslot_max_length = NRF_RAAL_TIMESLOT_DEFAULT_MAX_LENGTH;
m_config.timeslot_timeout = NRF_RAAL_TIMESLOT_DEFAULT_TIMEOUT;
m_config.lf_clk_accuracy_ppm = NRF_RAAL_DEFAULT_LF_CLK_ACCURACY_PPM;
calculate_config();
uint32_t err_code = sd_radio_session_open(signal_handler);
assert(err_code == NRF_SUCCESS);
(void)err_code;
#if (SD_VERSION >= BLE_ADV_SCHED_CFG_SUPPORT_MIN_SD_VERSION)
// Ensure that correct SoftDevice version is flashed.
if (SD_VERSION_GET(MBR_SIZE) >= BLE_ADV_SCHED_CFG_SUPPORT_MIN_SD_VERSION)
{
// Use improved Advertiser Role Scheduling configuration.
ble_opt_t opt;
memset(&opt, 0, sizeof(opt));
opt.common_opt.adv_sched_cfg.sched_cfg = ADV_SCHED_CFG_IMPROVED;
err_code = sd_ble_opt_set(BLE_COMMON_OPT_ADV_SCHED_CFG, &opt);
assert(err_code == NRF_SUCCESS);
(void)err_code;
}
#endif
m_initialized = true;
}
void nrf_raal_uninit(void)
{
assert(m_initialized);
uint32_t err_code = sd_radio_session_close();
assert(err_code == NRF_SUCCESS);
(void)err_code;
m_continuous = false;
m_timeslot_state = TIMESLOT_STATE_IDLE;
nrf_802154_pin_clr(PIN_DBG_TIMESLOT_ACTIVE);
}
void nrf_raal_continuous_mode_enter(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_CONTINUOUS_ENTER);
assert(m_initialized);
assert(!m_continuous);
m_continuous = true;
if (timeslot_is_idle())
{
timeslot_data_init();
timeslot_request();
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_CONTINUOUS_ENTER);
}
void nrf_raal_continuous_mode_exit(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_RAAL_CONTINUOUS_EXIT);
assert(m_initialized);
assert(m_continuous);
m_continuous = false;
// Emulate signal interrupt to inform SD about end of continuous mode.
if (timeslot_is_granted())
{
NVIC_SetPendingIRQ(RAAL_TIMER_IRQn);
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_RAAL_CONTINUOUS_EXIT);
}
void nrf_raal_continuous_ended(void)
{
// Intentionally empty.
}
bool nrf_raal_timeslot_request(uint32_t length_us)
{
uint32_t us_left;
if (!m_continuous || !timeslot_is_granted())
{
return false;
}
us_left = nrf_raal_timeslot_us_left_get();
assert((us_left >= nrf_802154_rx_duration_get(MAX_PACKET_SIZE,
true)) || timer_is_set_to_margin());
return length_us < us_left;
}
uint32_t nrf_raal_timeslot_us_left_get(void)
{
return safe_time_to_timeslot_end_get();
}

View file

@ -1,135 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module defines Radio Arbiter Abstraction Layer interface.
*
*/
#ifndef NRF_RAAL_SOFTDEVICE_H_
#define NRF_RAAL_SOFTDEVICE_H_
#include <stdbool.h>
#include <stdint.h>
#include <nrf_802154_utils.h>
#ifdef __cplusplus
extern "C" {
#endif
/** @brief RAAL Softdevice default parameters. */
#define NRF_RAAL_TIMESLOT_DEFAULT_LENGTH 6400
#define NRF_RAAL_TIMESLOT_DEFAULT_ALLOC_ITERS 5
#define NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN nrf_raal_softdevice_safe_margin_calc( \
NRF_RAAL_DEFAULT_LF_CLK_ACCURACY_PPM)
#define NRF_RAAL_TIMESLOT_DEFAULT_TIMEOUT 4500
#define NRF_RAAL_TIMESLOT_DEFAULT_MAX_LENGTH 120000000
#define NRF_RAAL_DEFAULT_LF_CLK_ACCURACY_PPM 500
#define NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN_LFRC_TICKS 4
#define NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN_CRYSTAL_TICKS 3
#define NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN_US 3
#define NRF_RAAL_PPM_THRESHOLD 500
#define NRF_RAAL_TIMESLOT_SAFE_MARGIN_TICKS(ppm) ((ppm >= NRF_RAAL_PPM_THRESHOLD) ? \
NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN_LFRC_TICKS \
: \
NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN_CRYSTAL_TICKS)
/**
* @brief Function used to calculate safe margin from LF clock accuracy in ppm unit.
*
* @param[in] ppm LF clock accuracy in ppm unit.
*/
#define nrf_raal_softdevice_safe_margin_calc(ppm) (NRF_802154_RTC_TICKS_TO_US( \
NRF_RAAL_TIMESLOT_SAFE_MARGIN_TICKS( \
ppm)) \
+ \
NRF_RAAL_TIMESLOT_DEFAULT_SAFE_MARGIN_US)
/** @brief RAAL Softdevice configuration parameters. */
typedef struct
{
/**
* @brief Timeslot length requested by the module in microseconds.
*/
uint32_t timeslot_length;
/**
* @brief Longest acceptable delay until the start of the requested timeslot in microseconds.
*/
uint32_t timeslot_timeout;
/**
* @brief Maximum single timeslot length created by extension processing in microseconds.
*/
uint32_t timeslot_max_length;
/**
* @brief Maximum number of iteration of dividing timeslot_length by factor of 2 performed by arbiter.
*/
uint16_t timeslot_alloc_iters;
/**
* @brief Safe margin before timeslot is finished and nrf_raal_timeslot_ended should be called in microseconds.
* @ref nrf_raal_softdevice_safe_margin_calc can be used to calculate proper value based on clock accuracy.
* This value can also be selected experimentally.
*/
uint16_t timeslot_safe_margin;
/**
* @brief Clock accuracy in ppm unit.
*/
uint16_t lf_clk_accuracy_ppm;
} nrf_raal_softdevice_cfg_t;
/**
* @brief Function used to inform RAAL client about Softdevice's SoC events.
*
*/
void nrf_raal_softdevice_soc_evt_handler(uint32_t evt_id);
/**
* @brief Function used to set non-default parameters of RAAL.
*
*/
void nrf_raal_softdevice_config(const nrf_raal_softdevice_cfg_t * p_cfg);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_RAAL_SOFTDEVICE_H_ */

View file

@ -1,460 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @file
* This file implements timer scheduler for the nRF 802.15.4 driver.
*
* This implementation supports scheduling of multiple timer instances and can be used from different contexts.
*
* @note Timer scheduler is secured against preemption and adding/removing different timers from different contexts,
* it shall not be used for adding/removing the same timer instance from two contexts at the same time.
*
*/
#include "nrf_802154_timer_sched.h"
#include <assert.h>
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#include <nrf.h>
#include "nrf_802154_debug.h"
#include "platform/lp_timer/nrf_802154_lp_timer.h"
#if defined(__ICCARM__)
_Pragma("diag_suppress=Pe167")
#endif
static volatile uint8_t m_timer_mutex; ///< Mutex for starting the timer.
static volatile uint8_t m_fired_mutex; ///< Mutex for the timer firing procedure.
static volatile uint8_t m_queue_changed_cntr; ///< Information that scheduler queue was modified.
static volatile nrf_802154_timer_t * mp_head; ///< Head of the running timers list.
/** @brief Non-blocking mutex for starting the timer.
*
* @retval true Mutex was acquired.
* @retval false Mutex could not be acquired.
*/
static inline bool mutex_trylock(volatile uint8_t * p_mutex)
{
do
{
volatile uint8_t mutex_value = __LDREXB(p_mutex);
if (mutex_value)
{
__CLREX();
return false;
}
}
while (__STREXB(1, p_mutex));
__DMB();
return true;
}
/** @brief Release mutex. */
static inline void mutex_unlock(volatile uint8_t * p_mutex)
{
__DMB();
*p_mutex = 0;
}
/** @brief Increment queue counter value to detect changes in the queue. */
static inline void queue_cntr_bump(void)
{
volatile uint8_t cntr;
do
{
cntr = __LDREXB(&m_queue_changed_cntr);
}
while (__STREXB(cntr + 1, &m_queue_changed_cntr));
__DMB();
}
/**
* @brief Check if @p time_1 is before @p time_2.
*
* @param[in] time_1 First time to compare.
* @param[in] time_2 Second time to compare.
*
* @return True if @p time_1 is before @p time_2, false otherwise.
*/
static inline bool is_time_before(uint32_t time_1, uint32_t time_2)
{
int32_t diff = time_1 - time_2;
return diff < 0;
}
/**
* @brief Check if @p p_timer_1 shall strike earlier than @p p_timer_2.
*
* @param[in] p_timer_1 A pointer to first timer to compare.
* @param[in] p_timer_2 A pointer to second timer to compare.
*
* @return True if @p p_timer_1 shall strike earlier than @p p_timer_2, false otherwise.
*/
static inline bool is_timer_prior(const nrf_802154_timer_t * p_timer_1,
const nrf_802154_timer_t * p_timer_2)
{
return is_time_before(p_timer_1->t0 + p_timer_1->dt, p_timer_2->t0 + p_timer_2->dt);
}
/**
* @brief Handle operation on timer with mutex protection.
*/
static inline void handle_timer(void)
{
volatile nrf_802154_timer_t * p_head;
uint8_t queue_cntr;
do
{
queue_cntr = m_queue_changed_cntr;
p_head = mp_head;
if (mutex_trylock(&m_timer_mutex))
{
if (p_head == NULL)
{
nrf_802154_lp_timer_stop();
}
else
{
uint32_t t0 = p_head->t0;
uint32_t dt = p_head->dt;
// Set the timer only if current HEAD wasn't removed - otherwise t0 and dt might've been modified
// between reading t0 and dt and not be a valid combination.
if (p_head == mp_head)
{
nrf_802154_lp_timer_start(t0, dt);
}
}
mutex_unlock(&m_timer_mutex);
}
}
while (queue_cntr != m_queue_changed_cntr);
}
/**
* @brief Remove timer from the queue
*
* @param [inout] p_timer Pointer to timer to remove from the queue.
*
* @retval true @sa handle_timer() shall be called by caller of this function.
* @retval false @sa handle_timer() shall not be called by the caller.
*/
static bool timer_remove(nrf_802154_timer_t * p_timer)
{
assert(p_timer != NULL);
nrf_802154_timer_t ** pp_item;
nrf_802154_timer_t * volatile p_next; // Volatile pointer to prevent compiler from removing any code related to this variable during optimization (IAR).
nrf_802154_timer_t * p_cur;
uint8_t queue_cntr;
bool timer_start;
bool timer_stop;
while (true)
{
queue_cntr = m_queue_changed_cntr;
pp_item = (nrf_802154_timer_t **)&mp_head;
p_next = NULL;
p_cur = NULL;
timer_start = false;
timer_stop = false;
// Find entry to remove
while (true)
{
p_cur = (nrf_802154_timer_t *)__LDREXW((uint32_t *)pp_item);
if ((p_cur == NULL) || (p_cur == p_timer))
{
break;
}
pp_item = &(p_cur->p_next);
}
if (queue_cntr != m_queue_changed_cntr)
{
// Higher priority modified the queue while iterating, try again.
continue;
}
if (p_cur == p_timer)
{
// Entry found.
p_next = p_cur->p_next;
// Restart timer when removing HEAD and other timer instance is pending.
if (p_cur == mp_head)
{
if (p_next != NULL)
{
timer_start = true;
}
else
{
timer_stop = true;
}
}
}
else
{
// Entry not found
__CLREX();
break;
}
if (!__STREXW((uint32_t)p_next, (uint32_t *)pp_item))
{
// Exit, if exclusive access succeeds.
queue_cntr_bump();
break;
}
}
// Write to the pointer next on removal to ensure that node removal is detected by
// lower pritority context in case it was going to be used.
if (p_cur != NULL)
{
uint32_t temp;
do
{
// This assignment is used to prevent compiler from removing exclusive load during optimization (IAR).
temp = __LDREXW((uint32_t *)&p_cur->p_next);
assert((void *)temp != p_cur);
}
while (__STREXW(temp, (uint32_t *)&p_cur->p_next));
}
return (timer_start || timer_stop);
}
void nrf_802154_timer_sched_init(void)
{
mp_head = NULL;
m_timer_mutex = 0;
m_fired_mutex = 0;
m_queue_changed_cntr = 0;
}
void nrf_802154_timer_sched_deinit(void)
{
nrf_802154_lp_timer_stop();
mp_head = NULL;
}
uint32_t nrf_802154_timer_sched_time_get(void)
{
return nrf_802154_lp_timer_time_get();
}
uint32_t nrf_802154_timer_sched_granularity_get(void)
{
return nrf_802154_lp_timer_granularity_get();
}
bool nrf_802154_timer_sched_time_is_in_future(uint32_t now, uint32_t t0, uint32_t dt)
{
uint32_t target_time = t0 + dt;
int32_t difference = target_time - now;
return difference > 0;
}
uint32_t nrf_802154_timer_sched_remaining_time_get(const nrf_802154_timer_t * p_timer)
{
assert(p_timer != NULL);
uint32_t now = nrf_802154_lp_timer_time_get();
uint32_t expiration = p_timer->t0 + p_timer->dt;
int32_t remaining = expiration - now;
if (remaining > 0)
{
return (uint32_t)remaining;
}
else
{
return 0ul;
}
}
void nrf_802154_timer_sched_add(nrf_802154_timer_t * p_timer, bool round_up)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_TSCH_ADD);
assert(p_timer != NULL);
assert(p_timer->callback != NULL);
if (round_up)
{
p_timer->dt += nrf_802154_lp_timer_granularity_get() - 1;
}
if (timer_remove(p_timer))
{
handle_timer();
}
nrf_802154_timer_t ** pp_item;
nrf_802154_timer_t * p_next;
uint8_t queue_cntr;
while (true)
{
queue_cntr = m_queue_changed_cntr;
pp_item = (nrf_802154_timer_t **)&mp_head;
p_next = NULL;
// Search the current queue to find appropriate position to insert timer.
while (true)
{
nrf_802154_timer_t * p_cur = (nrf_802154_timer_t *)__LDREXW((uint32_t *)pp_item);
assert(p_cur != p_timer);
if (p_cur == NULL)
{
// No HEAD or insert at the end.
p_next = NULL;
break;
}
if (is_timer_prior(p_timer, p_cur))
{
// Insert at the beginning with existing HEAD or somewhere in the middle.
p_next = p_cur;
break;
}
pp_item = &(p_cur->p_next);
}
if (queue_cntr != m_queue_changed_cntr)
{
// Higher priority modified the queue while iterating, try again.
continue;
}
assert(p_next != p_timer);
p_timer->p_next = p_next;
if (!__STREXW((uint32_t)p_timer, (uint32_t *)pp_item))
{
// Exit, if exclusive access succeeds.
queue_cntr_bump();
break;
}
}
if (mp_head == p_timer)
{
handle_timer();
}
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_TSCH_ADD);
}
void nrf_802154_timer_sched_remove(nrf_802154_timer_t * p_timer)
{
if (timer_remove(p_timer))
{
handle_timer();
}
}
bool nrf_802154_timer_sched_is_running(nrf_802154_timer_t * p_timer)
{
uint8_t queue_cntr;
bool result;
do
{
result = false;
queue_cntr = m_queue_changed_cntr;
for (volatile nrf_802154_timer_t * p_cur = mp_head;
p_cur != NULL;
p_cur = p_cur->p_next)
{
if (p_cur == p_timer)
{
result = true;
break;
}
}
}
while (queue_cntr != m_queue_changed_cntr);
return result;
}
void nrf_802154_lp_timer_fired(void)
{
nrf_802154_log(EVENT_TRACE_ENTER, FUNCTION_TSCH_FIRED);
if (mutex_trylock(&m_fired_mutex))
{
nrf_802154_timer_t * p_timer = (nrf_802154_timer_t *)mp_head;
if (p_timer != NULL)
{
nrf_802154_timer_callback_t callback = p_timer->callback;
void * p_context = p_timer->p_context;
(void)timer_remove(p_timer);
if (callback != NULL)
{
callback(p_context);
}
}
mutex_unlock(&m_fired_mutex);
}
handle_timer();
nrf_802154_log(EVENT_TRACE_EXIT, FUNCTION_TSCH_FIRED);
}

View file

@ -1,174 +0,0 @@
/* Copyright (c) 2017 - 2018, 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 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.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief This module provides timer scheduling functionality for the 802.15.4 driver.
*
* Timer module should be used to implement strict timing features specified in IEEE 802.15.4 like:
* * CSL,
* * Timing out waiting for ACK frames,
* * CSMA/CA,
* * Inter-frame spacing: SIFS, LIFS (note that AIFS is implemented without using timer module).
*
* @note Current implementation supports only single one-shot timer. It may be extended to support
* timer scheduling and repetitive timers if needed.
*/
#ifndef NRF_802154_TIMER_SCHED_H_
#define NRF_802154_TIMER_SCHED_H_
#include <stdbool.h>
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_802154_timer_sched Timer Scheduler module for the 802.15.4 driver
* @{
* @ingroup nrf_802154_timer_sched
* @brief Timer Scheduler module for the 802.15.4 driver.
*
*/
/**
* @brief Type of function called when timer fires.
*
* @param[inout] p_context Pointer to user-defined memory location. May be NULL.
*/
typedef void (* nrf_802154_timer_callback_t)(void * p_context);
/**
* @brief Type for driver instance.
*/
typedef struct nrf_802154_timer_s nrf_802154_timer_t;
/**
* @brief Structure containing timer data used by timer module.
*/
struct nrf_802154_timer_s
{
uint32_t t0; ///< Base time of the timer [us]
uint32_t dt; ///< Timer expiration delta from @p t0 [us]
nrf_802154_timer_callback_t callback; ///< Callback function called when timer expires
void * p_context; ///< User-defined context passed to callback function
nrf_802154_timer_t * p_next; ///< A pointer to the next running timer
};
/**
* @brief Initialize the timer scheduler.
*/
void nrf_802154_timer_sched_init(void);
/**
* @brief Deinitialize the timer scheduler.
*/
void nrf_802154_timer_sched_deinit(void);
/**
* @brief Get current time.
*
* This function is useful to set base time in @sa nrf_802154_timer_t structure.
*
* @return Current time in microseconds [us].
*/
uint32_t nrf_802154_timer_sched_time_get(void);
/**
* @brief Get granularity of the timer that runs the timer scheduler.
*
* @return Granularity of the timer in microseconds [us].
*/
uint32_t nrf_802154_timer_sched_granularity_get(void);
/**
* @brief Check if given time is in future.
*
* @param[in] now Current time. @sa nrf_802154_timer_sched_time_get()
* @param[in] t0 Base of time compared with @p now.
* @param[in] dt Time delta from @p t0 compared with @p now.
*
* @retval true Given time @p t0 @p dt is in future (compared to given @p now).
* @retval false Given time @p t0 @p dt is not in future (compared to given @p now).
*/
bool nrf_802154_timer_sched_time_is_in_future(uint32_t now, uint32_t t0, uint32_t dt);
/**
* @brief Get timer time remaining to expiration.
*
* @param[in] p_timer Pointer to the timer to check remaining time.
*
* @retval remaining time [us] or 0 if timer has already expired.
*/
uint32_t nrf_802154_timer_sched_remaining_time_get(const nrf_802154_timer_t * p_timer);
/**
* @brief Start given timer and add it to the scheduler.
*
* @note Fields t0, dt, callback and p_context should be filled in @p p_timer prior to calling this
* function; callback field cannot be NULL.
*
* @note Due to timer granularity the callback function cannot be called exactly at specified time.
* Use @p round_up to specify if given timer should be expired before or after time given in
* the @p p_timer structure. The dt field of the @p p_timer is updated with the rounded up value.
*
* @param[inout] p_timer Pointer to the timer to start and add to the scheduler.
* @param[in] round_up True if timer should expire after specified time, false if it should
* expire before.
*/
void nrf_802154_timer_sched_add(nrf_802154_timer_t * p_timer, bool round_up);
/**
* @brief Stop given timer and remove it from the scheduler.
*
* @param[inout] p_timer Pointer to the timer to stop and remove from the scheduler.
*/
void nrf_802154_timer_sched_remove(nrf_802154_timer_t * p_timer);
/**
* @brief Check if given timer is already scheduled.
*
* @param[in] p_timer Pointer to the timer to check.
*
* @retval true Given timer is already scheduled.
* @retval false Given timer is not scheduled.
*/
bool nrf_802154_timer_sched_is_running(nrf_802154_timer_t * p_timer);
/**
*@}
**/
#ifdef __cplusplus
}
#endif
#endif /* NRF_802154_TIMER_SCHED_H_ */

View file

@ -1,44 +0,0 @@
nrfx
####
Origin:
https://github.com/NordicSemiconductor/nrfx/tree/v1.7.2
Status:
v1.7.2
Purpose:
With added proper shims adapting it to Zephyr's APIs, nrfx will provide
peripheral drivers for Nordic SoCs.
Description:
nrfx is a standalone set of drivers for peripherals present in Nordic
Semiconductor's SoCs. It originated as an extract from the nRF5 SDK.
The intention was to provide drivers that can be used in various
environments without the necessity to integrate other parts of the SDK
into them. For the user's convenience, the drivers come with the MDK
package. This package contains definitions of register structures and
bitfields for all supported SoCs, as well as startup and initialization
files for them.
Only relevant files from nrfx are imported. For instance, template files,
the ones with startup code or strictly related to the installation of IRQs
in the vector table are omitted in the import.
Dependencies:
CMSIS header files
URL:
https://github.com/NordicSemiconductor/nrfx
commit:
13a7de7de72cfd444af468f11c0dbb9db7a26172
Maintained-by:
External
License:
BSD-3-Clause
License Link:
https://github.com/NordicSemiconductor/nrfx/blob/v1.7.2/LICENSE

View file

@ -1,150 +0,0 @@
/*
* Copyright (c) 2016 - 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRF_BITMASK_H
#define NRF_BITMASK_H
#include <nrfx.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrf_bitmask Bitmask module
* @{
* @ingroup nrfx
* @brief Bitmask managing module.
*/
/** @brief Macro for getting index of byte in byte stream where @c abs_bit is put. */
#define BITMASK_BYTE_GET(abs_bit) ((abs_bit)/8)
/** @brief Macro for getting relative index of bit in byte. */
#define BITMASK_RELBIT_GET(abs_bit) ((abs_bit) & 0x00000007)
/**
* @brief Function for checking if bit in the multi-byte bit mask is set.
*
* @param[in] bit Bit index.
* @param[in] p_mask Pointer to mask with bit fields.
*
* @return 0 if bit is not set, positive value otherwise.
*/
__STATIC_INLINE uint32_t nrf_bitmask_bit_is_set(uint32_t bit, void const * p_mask)
{
uint8_t const * p_mask8 = (uint8_t const *)p_mask;
uint32_t byte_idx = BITMASK_BYTE_GET(bit);
bit = BITMASK_RELBIT_GET(bit);
return (1 << bit) & p_mask8[byte_idx];
}
/**
* @brief Function for setting a bit in the multi-byte bit mask.
*
* @param[in] bit Bit index.
* @param[in] p_mask Pointer to mask with bit fields.
*/
__STATIC_INLINE void nrf_bitmask_bit_set(uint32_t bit, void * p_mask)
{
uint8_t * p_mask8 = (uint8_t *)p_mask;
uint32_t byte_idx = BITMASK_BYTE_GET(bit);
bit = BITMASK_RELBIT_GET(bit);
p_mask8[byte_idx] |= (1 << bit);
}
/**
* @brief Function for clearing a bit in the multi-byte bit mask.
*
* @param[in] bit Bit index.
* @param[in] p_mask Pointer to mask with bit fields.
*/
__STATIC_INLINE void nrf_bitmask_bit_clear(uint32_t bit, void * p_mask)
{
uint8_t * p_mask8 = (uint8_t *)p_mask;
uint32_t byte_idx = BITMASK_BYTE_GET(bit);
bit = BITMASK_RELBIT_GET(bit);
p_mask8[byte_idx] &= ~(1 << bit);
}
/**
* @brief Function for performing bitwise OR operation on two multi-byte bit masks.
*
* @param[in] p_mask1 Pointer to the first bit mask.
* @param[in] p_mask2 Pointer to the second bit mask.
* @param[in] p_out_mask Pointer to the output bit mask.
* @param[in] length Length of output mask in bytes.
*/
__STATIC_INLINE void nrf_bitmask_masks_or(void const * p_mask1,
void const * p_mask2,
void * p_out_mask,
uint32_t length)
{
uint8_t const * p_mask8_1 = (uint8_t const *)p_mask1;
uint8_t const * p_mask8_2 = (uint8_t const *)p_mask2;
uint8_t * p_mask8_out = (uint8_t *)p_out_mask;
uint32_t i;
for (i = 0; i < length; i++)
{
p_mask8_out[i] = p_mask8_1[i] | p_mask8_2[i];
}
}
/**
* @brief Function for performing bitwise AND operation on two multi-byte bit masks.
*
* @param[in] p_mask1 Pointer to the first bit mask.
* @param[in] p_mask2 Pointer to the second bit mask.
* @param[in] p_out_mask Pointer to the output bit mask.
* @param[in] length Length of output mask in bytes.
*/
__STATIC_INLINE void nrf_bitmask_masks_and(void const * p_mask1,
void const * p_mask2,
void * p_out_mask,
uint32_t length)
{
uint8_t const * p_mask8_1 = (uint8_t const *)p_mask1;
uint8_t const * p_mask8_2 = (uint8_t const *)p_mask2;
uint8_t * p_mask8_out = (uint8_t *)p_out_mask;
uint32_t i;
for (i = 0; i < length; i++)
{
p_mask8_out[i] = p_mask8_1[i] & p_mask8_2[i];
}
}
/** @} */
#ifdef __cplusplus
}
#endif
#endif // NRF_BITMASK_H

View file

@ -1,280 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_ADC_H__
#define NRFX_ADC_H__
#include <nrfx.h>
#include <hal/nrf_adc.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_adc ADC driver
* @{
* @ingroup nrf_adc
* @brief Analog-to-Digital Converter (ADC) peripheral driver.
*/
/** @brief Driver event types. */
typedef enum
{
NRFX_ADC_EVT_DONE, ///< Event generated when the buffer is filled with samples.
NRFX_ADC_EVT_SAMPLE, ///< Event generated when the requested channel is sampled.
} nrfx_adc_evt_type_t;
/** @brief ADC driver DONE event structure. */
typedef struct
{
nrf_adc_value_t * p_buffer; ///< Pointer to the buffer with converted samples.
uint16_t size; ///< Number of samples in the buffer.
} nrfx_adc_done_evt_t;
/** @brief SAMPLE event structure. */
typedef struct
{
nrf_adc_value_t sample; ///< Converted sample.
} nrfx_adc_sample_evt_t;
/** @brief ADC driver event. */
typedef struct
{
nrfx_adc_evt_type_t type; ///< Event type.
union
{
nrfx_adc_done_evt_t done; ///< Data for DONE event.
nrfx_adc_sample_evt_t sample; ///< Data for SAMPLE event.
} data; ///< Union to store event data.
} nrfx_adc_evt_t;
/** @brief Macro for initializing the ADC channel with the default configuration. */
#define NRFX_ADC_DEFAULT_CHANNEL(analog_input) \
{ \
NULL, \
{ \
.resolution = NRF_ADC_CONFIG_RES_10BIT, \
.scaling = NRF_ADC_CONFIG_SCALING_INPUT_FULL_SCALE, \
.reference = NRF_ADC_CONFIG_REF_VBG, \
.input = (analog_input), \
.extref = NRF_ADC_CONFIG_EXTREFSEL_NONE \
} \
}
/** @brief Forward declaration of the nrfx_adc_channel_t type. */
typedef struct nrfx_adc_channel_s nrfx_adc_channel_t;
/**
* @brief ADC channel.
*
* This structure is defined by the user and used by the driver. Therefore, it should
* not be defined on the stack as a local variable.
*/
struct nrfx_adc_channel_s
{
nrfx_adc_channel_t * p_next; ///< Pointer to the next enabled channel (for internal use).
nrf_adc_config_t config; ///< ADC configuration for the current channel.
};
/** @brief ADC configuration. */
typedef struct
{
uint8_t interrupt_priority; ///< Priority of ADC interrupt.
} nrfx_adc_config_t;
/** @brief ADC default configuration. */
#define NRFX_ADC_DEFAULT_CONFIG \
{ \
.interrupt_priority = NRFX_ADC_CONFIG_IRQ_PRIORITY \
}
/**
* @brief User event handler prototype.
*
* This function is called when the requested number of samples has been processed.
*
* @param p_event Event.
*/
typedef void (*nrfx_adc_event_handler_t)(nrfx_adc_evt_t const * p_event);
/**
* @brief Function for initializing the ADC.
*
* If a valid event handler is provided, the driver is initialized in non-blocking mode.
* If event_handler is NULL, the driver works in blocking mode.
*
* @param[in] p_config Pointer to the structure with the initial configuration.
* @param[in] event_handler Event handler provided by the user.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver is already initialized.
*/
nrfx_err_t nrfx_adc_init(nrfx_adc_config_t const * p_config,
nrfx_adc_event_handler_t event_handler);
/**
* @brief Function for uninitializing the ADC.
*
* This function stops all ongoing conversions and disables all channels.
*/
void nrfx_adc_uninit(void);
/**
* @brief Function for enabling an ADC channel.
*
* This function configures and enables the channel. When @ref nrfx_adc_buffer_convert is
* called, all channels that have been enabled with this function are sampled.
*
* This function can be called only when there is no conversion in progress
* (the ADC is not busy).
*
* @note The channel instance variable @p p_channel is used by the driver as an item
* in a list. Therefore, it cannot be an automatic variable that is located on the stack.
*
* @param[in] p_channel Pointer to the channel instance.
*/
void nrfx_adc_channel_enable(nrfx_adc_channel_t * const p_channel);
/**
* @brief Function for disabling an ADC channel.
*
* This function can be called only when there is no conversion in progress
* (the ADC is not busy).
*
* @param p_channel Pointer to the channel instance.
*/
void nrfx_adc_channel_disable(nrfx_adc_channel_t * const p_channel);
/**
* @brief Function for disabling all ADC channels.
*
* This function can be called only when there is no conversion in progress
* (the ADC is not busy).
*/
void nrfx_adc_all_channels_disable(void);
/**
* @brief Function for starting ADC sampling.
*
* This function triggers single ADC sampling. If more than one channel is enabled, the driver
* emulates scanning and all channels are sampled in the order they were enabled.
*/
void nrfx_adc_sample(void);
/**
* @brief Function for executing a single ADC conversion.
*
* This function selects the desired input and starts a single conversion. If a valid pointer
* is provided for the result, the function blocks until the conversion is completed. Otherwise, the
* function returns when the conversion is started, and the result is provided in an event (driver
* must be initialized in non-blocking mode, otherwise an assertion will fail). The function will
* fail if ADC is busy. The channel does not need to be enabled to perform a single conversion.
*
* @param[in] p_channel Channel.
* @param[out] p_value Pointer to the location where the result is to be placed. Unless NULL is
* provided, the function is blocking.
*
* @retval NRFX_SUCCESS Conversion was successful.
* @retval NRFX_ERROR_BUSY The ADC driver is busy.
*/
nrfx_err_t nrfx_adc_sample_convert(nrfx_adc_channel_t const * const p_channel,
nrf_adc_value_t * p_value);
/**
* @brief Function for converting data to the buffer.
*
* If the driver is initialized in non-blocking mode, this function returns when the first
* conversion is set up. When the buffer is filled, the application is notified by the event
* handler. If the driver is initialized in blocking mode, the function returns when the buffer is
* filled.
*
* Conversion is done on all enabled channels, but it is not triggered by this
* function. This function will prepare the ADC for sampling and then
* wait for the SAMPLE task. Sampling can be triggered manually by the @ref
* nrfx_adc_sample function or by PPI using the @ref NRF_ADC_TASK_START task.
*
* @note If more than one channel is enabled, the function emulates scanning, and
* a single START task will trigger conversion on all enabled channels. For example:
* If 3 channels are enabled and the user requests 6 samples, the completion event
* handler will be called after 2 START tasks.
*
* @note The application must adjust the sampling frequency. The maximum frequency
* depends on the sampling timer and the maximum latency of the ADC interrupt. If
* an interrupt is not handled before the next sampling is triggered, the sample
* will be lost.
*
* @param[in] buffer Result buffer.
* @param[in] size Buffer size in samples.
*
* @retval NRFX_SUCCESS Conversion was successful.
* @retval NRFX_ERROR_BUSY The driver is busy.
*/
nrfx_err_t nrfx_adc_buffer_convert(nrf_adc_value_t * buffer, uint16_t size);
/**
* @brief Function for retrieving the ADC state.
*
* @retval true The ADC is busy.
* @retval false The ADC is ready.
*/
bool nrfx_adc_is_busy(void);
/**
* @brief Function for getting the address of the ADC START task.
*
* This function is used to get the address of the START task, which can be used to trigger ADC
* conversion.
*
* @return Start task address.
*/
__STATIC_INLINE uint32_t nrfx_adc_start_task_get(void);
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE uint32_t nrfx_adc_start_task_get(void)
{
return nrf_adc_task_address_get(NRF_ADC_TASK_START);
}
#endif
/** @} */
void nrfx_adc_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_ADC_H__

View file

@ -1,197 +0,0 @@
/*
* Copyright (c) 2016 - 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_CLOCK_H__
#define NRFX_CLOCK_H__
#include <nrfx.h>
#include <hal/nrf_clock.h>
#include <nrfx_power_clock.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_clock CLOCK driver
* @{
* @ingroup nrf_clock
* @brief CLOCK peripheral driver.
*/
/** @brief Clock events. */
typedef enum
{
NRFX_CLOCK_EVT_HFCLK_STARTED, ///< HFCLK has been started.
NRFX_CLOCK_EVT_LFCLK_STARTED, ///< LFCLK has been started.
NRFX_CLOCK_EVT_CTTO, ///< Calibration timeout.
NRFX_CLOCK_EVT_CAL_DONE ///< Calibration has been done.
} nrfx_clock_evt_type_t;
/**
* @brief Clock event handler.
*
* @param[in] event Event.
*/
typedef void (*nrfx_clock_event_handler_t)(nrfx_clock_evt_type_t event);
/**
* @brief Function for initializing internal structures in the nrfx_clock module.
*
* After initialization, the module is in power off state (clocks are not started).
*
* @param[in] event_handler Event handler provided by the user.
* Must not be NULL.
*
* @retval NRFX_SUCCESS The procedure is successful.
* @retval NRFX_ERROR_ALREADY_INITIALIZED The driver is already initialized.
*/
nrfx_err_t nrfx_clock_init(nrfx_clock_event_handler_t event_handler);
/** @brief Function for enabling interrupts in the clock module. */
void nrfx_clock_enable(void);
/** @brief Function for disabling interrupts in the clock module. */
void nrfx_clock_disable(void);
/** @brief Function for uninitializing the clock module. */
void nrfx_clock_uninit(void);
/** @brief Function for starting the LFCLK. */
void nrfx_clock_lfclk_start(void);
/** @brief Function for stopping the LFCLK. */
void nrfx_clock_lfclk_stop(void);
/**
* @brief Function for checking the LFCLK state.
*
* @retval true The LFCLK is running.
* @retval false The LFCLK is not running.
*/
__STATIC_INLINE bool nrfx_clock_lfclk_is_running(void);
/** @brief Function for starting the high-accuracy source HFCLK. */
void nrfx_clock_hfclk_start(void);
/** @brief Function for stopping the external high-accuracy source HFCLK. */
void nrfx_clock_hfclk_stop(void);
/**
* @brief Function for checking the HFCLK state.
*
* @retval true The HFCLK is running (XTAL source).
* @retval false The HFCLK is not running.
*/
__STATIC_INLINE bool nrfx_clock_hfclk_is_running(void);
/**
* @brief Function for starting the calibration of internal LFCLK.
*
* This function starts the calibration process. The process cannot be aborted. LFCLK and HFCLK
* must be running before this function is called.
*
* @retval NRFX_SUCCESS The procedure is successful.
* @retval NRFX_ERROR_INVALID_STATE The low-frequency of high-frequency clock is off.
* @retval NRFX_ERROR_BUSY Clock is in the calibration phase.
*/
nrfx_err_t nrfx_clock_calibration_start(void);
/**
* @brief Function for checking if calibration is in progress.
*
* This function indicates that the system is in calibration phase.
*
* @retval NRFX_SUCCESS The procedure is successful.
* @retval NRFX_ERROR_BUSY Clock is in the calibration phase.
*/
nrfx_err_t nrfx_clock_is_calibrating(void);
/**
* @brief Function for starting calibration timer.
*
* @param[in] interval Time after which the CTTO event and interrupt will be generated (in 0.25 s units).
*/
void nrfx_clock_calibration_timer_start(uint8_t interval);
/** @brief Function for stopping the calibration timer. */
void nrfx_clock_calibration_timer_stop(void);
/**@brief Function for returning a requested task address for the clock driver module.
*
* @param[in] task One of the peripheral tasks.
*
* @return Task address.
*/
__STATIC_INLINE uint32_t nrfx_clock_ppi_task_addr(nrf_clock_task_t task);
/**@brief Function for returning a requested event address for the clock driver module.
*
* @param[in] event One of the peripheral events.
*
* @return Event address.
*/
__STATIC_INLINE uint32_t nrfx_clock_ppi_event_addr(nrf_clock_event_t event);
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE uint32_t nrfx_clock_ppi_task_addr(nrf_clock_task_t task)
{
return nrf_clock_task_address_get(task);
}
__STATIC_INLINE uint32_t nrfx_clock_ppi_event_addr(nrf_clock_event_t event)
{
return nrf_clock_event_address_get(event);
}
__STATIC_INLINE bool nrfx_clock_hfclk_is_running(void)
{
return nrf_clock_hf_is_running(NRF_CLOCK_HFCLK_HIGH_ACCURACY);
}
__STATIC_INLINE bool nrfx_clock_lfclk_is_running(void)
{
return nrf_clock_lf_is_running();
}
#endif //SUPPRESS_INLINE_IMPLEMENTATION
/** @} */
void nrfx_clock_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_CLOCK_H__

View file

@ -1,239 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_COMP_H__
#define NRFX_COMP_H__
#include <nrfx.h>
#include <hal/nrf_comp.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_comp COMP driver
* @{
* @ingroup nrf_comp
* @brief Comparator (COMP) peripheral driver.
*/
/**
* @brief Macro for converting the threshold voltage to an integer value
* (needed by the COMP_TH register).
*
* @param[in] vol Voltage to be changed to COMP_TH register value. This value
* must not be smaller than reference voltage divided by 64.
* @param[in] ref Reference voltage.
*/
#define NRFX_VOLTAGE_THRESHOLD_TO_INT(vol, ref) \
(uint8_t)(((vol) > ((ref) / 64)) ? (NRFX_ROUNDED_DIV((vol) * 64,(ref)) - 1) : 0)
/**
* @brief COMP event handler function type.
*
* @param[in] event COMP event.
*/
typedef void (* nrfx_comp_event_handler_t)(nrf_comp_event_t event);
/** @brief COMP shortcut masks. */
typedef enum
{
NRFX_COMP_SHORT_STOP_AFTER_CROSS_EVT = COMP_SHORTS_CROSS_STOP_Msk, /*!< Shortcut between the CROSS event and the STOP task. */
NRFX_COMP_SHORT_STOP_AFTER_UP_EVT = COMP_SHORTS_UP_STOP_Msk, /*!< Shortcut between the UP event and the STOP task. */
NRFX_COMP_SHORT_STOP_AFTER_DOWN_EVT = COMP_SHORTS_DOWN_STOP_Msk /*!< Shortcut between the DOWN event and the STOP task. */
} nrfx_comp_short_mask_t;
/** @brief COMP events masks. */
typedef enum
{
NRFX_COMP_EVT_EN_CROSS_MASK = COMP_INTENSET_CROSS_Msk, /*!< CROSS event (generated after VIN+ == VIN-). */
NRFX_COMP_EVT_EN_UP_MASK = COMP_INTENSET_UP_Msk, /*!< UP event (generated when VIN+ crosses VIN- while increasing). */
NRFX_COMP_EVT_EN_DOWN_MASK = COMP_INTENSET_DOWN_Msk, /*!< DOWN event (generated when VIN+ crosses VIN- while decreasing). */
NRFX_COMP_EVT_EN_READY_MASK = COMP_INTENSET_READY_Msk /*!< READY event (generated when the module is ready). */
} nrfx_comp_evt_en_mask_t;
/** @brief COMP configuration. */
typedef struct
{
nrf_comp_ref_t reference; /**< Reference selection. */
nrf_comp_ext_ref_t ext_ref; /**< External analog reference selection. */
nrf_comp_main_mode_t main_mode; /**< Main operation mode. */
nrf_comp_th_t threshold; /**< Structure holding THDOWN and THUP values needed by the COMP_TH register. */
nrf_comp_sp_mode_t speed_mode; /**< Speed and power mode. */
nrf_comp_hyst_t hyst; /**< Comparator hysteresis. */
#if defined (COMP_ISOURCE_ISOURCE_Msk) || defined (__NRFX_DOXYGEN__)
nrf_isource_t isource; /**< Current source selected on analog input. */
#endif
nrf_comp_input_t input; /**< Input to be monitored. */
uint8_t interrupt_priority; /**< Interrupt priority. */
} nrfx_comp_config_t;
/** @brief COMP threshold default configuration. */
#define NRFX_COMP_CONFIG_TH \
{ \
.th_down = NRFX_VOLTAGE_THRESHOLD_TO_INT(0.5, 1.8), \
.th_up = NRFX_VOLTAGE_THRESHOLD_TO_INT(1.5, 1.8) \
}
/** @brief COMP driver default configuration including the COMP HAL configuration. */
#if defined (COMP_ISOURCE_ISOURCE_Msk) || defined (__NRFX_DOXYGEN__)
#define NRFX_COMP_DEFAULT_CONFIG(_input) \
{ \
.reference = (nrf_comp_ref_t)NRFX_COMP_CONFIG_REF, \
.ext_ref = NRF_COMP_EXT_REF_0, \
.main_mode = (nrf_comp_main_mode_t)NRFX_COMP_CONFIG_MAIN_MODE, \
.threshold = NRFX_COMP_CONFIG_TH, \
.speed_mode = (nrf_comp_sp_mode_t)NRFX_COMP_CONFIG_SPEED_MODE, \
.hyst = (nrf_comp_hyst_t)NRFX_COMP_CONFIG_HYST, \
.isource = (nrf_isource_t)NRFX_COMP_CONFIG_ISOURCE, \
.input = (nrf_comp_input_t)_input, \
.interrupt_priority = NRFX_COMP_CONFIG_IRQ_PRIORITY \
}
#else
#define NRFX_COMP_DEFAULT_CONFIG(_input) \
{ \
.reference = (nrf_comp_ref_t)NRFX_COMP_CONFIG_REF, \
.ext_ref = NRF_COMP_EXT_REF_0, \
.main_mode = (nrf_comp_main_mode_t)NRFX_COMP_CONFIG_MAIN_MODE, \
.threshold = NRFX_COMP_CONFIG_TH, \
.speed_mode = (nrf_comp_sp_mode_t)NRFX_COMP_CONFIG_SPEED_MODE, \
.hyst = (nrf_comp_hyst_t)NRFX_COMP_CONFIG_HYST, \
.input = (nrf_comp_input_t)_input, \
.interrupt_priority = NRFX_COMP_CONFIG_IRQ_PRIORITY \
}
#endif
/**
* @brief Function for initializing the COMP driver.
*
* This function initializes the COMP driver, but does not enable the peripheral or any interrupts.
* To start the driver, call the function @ref nrfx_comp_start() after initialization.
*
* @param[in] p_config Pointer to the structure with the initial configuration.
* @param[in] event_handler Event handler provided by the user.
* Must not be NULL.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver has already been initialized.
* @retval NRFX_ERROR_BUSY The LPCOMP peripheral is already in use.
* This is possible only if @ref nrfx_prs module
* is enabled.
*/
nrfx_err_t nrfx_comp_init(nrfx_comp_config_t const * p_config,
nrfx_comp_event_handler_t event_handler);
/**
* @brief Function for uninitializing the COMP driver.
*
* This function uninitializes the COMP driver. The COMP peripheral and
* its interrupts are disabled, and local variables are cleaned. After this call, you must
* initialize the driver again by calling nrfx_comp_init() if you want to use it.
*
* @sa nrfx_comp_stop
*/
void nrfx_comp_uninit(void);
/**
* @brief Function for setting the analog input.
*
* @param[in] psel COMP analog pin selection.
*/
void nrfx_comp_pin_select(nrf_comp_input_t psel);
/**
* @brief Function for starting the COMP peripheral and interrupts.
*
* Before calling this function, the driver must be initialized. This function
* enables the COMP peripheral and its interrupts.
*
* @param[in] comp_evt_en_mask Mask of events to be enabled. This parameter is to be built as
* an OR of elements from @ref nrfx_comp_evt_en_mask_t.
* @param[in] comp_shorts_mask Mask of shortcuts to be enabled. This parameter is to be built as
* an OR of elements from @ref nrfx_comp_short_mask_t.
*
* @sa nrfx_comp_init
*/
void nrfx_comp_start(uint32_t comp_evt_en_mask, uint32_t comp_shorts_mask);
/**
* @brief Function for stopping the COMP peripheral.
*
* Before calling this function, the driver must be enabled. This function disables the COMP
* peripheral and its interrupts.
*
* @sa nrfx_comp_uninit
*/
void nrfx_comp_stop(void);
/**
* @brief Function for copying the current state of the comparator result to the RESULT register.
*
* @retval 0 The input voltage is below the threshold (VIN+ < VIN-).
* @retval 1 The input voltage is above the threshold (VIN+ > VIN-).
*/
uint32_t nrfx_comp_sample(void);
/**
* @brief Function for getting the address of a COMP task.
*
* @param[in] task COMP task.
*
* @return Address of the given COMP task.
*/
__STATIC_INLINE uint32_t nrfx_comp_task_address_get(nrf_comp_task_t task)
{
return (uint32_t)nrf_comp_task_address_get(task);
}
/**
* @brief Function for getting the address of a COMP event.
*
* @param[in] event COMP event.
*
* @return Address of the given COMP event.
*/
__STATIC_INLINE uint32_t nrfx_comp_event_address_get(nrf_comp_event_t event)
{
return (uint32_t)nrf_comp_event_address_get(event);
}
/** @} */
void nrfx_comp_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_COMP_H__

View file

@ -1,176 +0,0 @@
/*
* Copyright (c) 2018 - 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_DPPI_H__
#define NRFX_DPPI_H__
#include <nrfx.h>
#include <hal/nrf_dppi.h>
/**
* @defgroup nrfx_dppi DPPI allocator
* @{
* @ingroup nrf_dppi
* @brief Distributed Programmable Peripheral Interconnect (DPPI) allocator.
*/
#ifdef __cplusplus
extern "C" {
#endif
/** @brief Function for freeing all allocated channels and groups. */
void nrfx_dppi_free(void);
/**
* @brief Function for allocating a DPPI channel.
* @details This function allocates the first unused DPPI channel.
*
* @param[out] p_channel Pointer to the DPPI channel number that has been allocated.
*
* @retval NRFX_SUCCESS The channel was successfully allocated.
* @retval NRFX_ERROR_NO_MEM There is no available channel to be used.
*/
nrfx_err_t nrfx_dppi_channel_alloc(uint8_t * p_channel);
/**
* @brief Function for freeing a DPPI channel.
* @details This function also disables the chosen channel.
*
* @param[in] channel DPPI channel to be freed.
*
* @retval NRFX_SUCCESS The channel was successfully freed.
* @retval NRFX_ERROR_INVALID_PARAM The specified channel is not allocated.
*/
nrfx_err_t nrfx_dppi_channel_free(uint8_t channel);
/**
* @brief Function for enabling a DPPI channel.
*
* @param[in] channel DPPI channel to be enabled.
*
* @retval NRFX_SUCCESS The channel was successfully enabled.
* @retval NRFX_ERROR_INVALID_PARAM The specified channel is not allocated.
*/
nrfx_err_t nrfx_dppi_channel_enable(uint8_t channel);
/**
* @brief Function for disabling a DPPI channel.
*
* @param[in] channel DPPI channel to be disabled.
*
* @retval NRFX_SUCCESS The channel was successfully disabled.
* @retval NRFX_ERROR_INVALID_PARAM The specified channel is not allocated.
*/
nrfx_err_t nrfx_dppi_channel_disable(uint8_t channel);
/**
* @brief Function for allocating a DPPI channel group.
* @details This function allocates the first unused DPPI group.
*
* @param[out] p_group Pointer to the DPPI channel group that has been allocated.
*
* @retval NRFX_SUCCESS The channel group was successfully allocated.
* @retval NRFX_ERROR_NO_MEM There is no available channel group to be used.
*/
nrfx_err_t nrfx_dppi_group_alloc(nrf_dppi_channel_group_t * p_group);
/**
* @brief Function for freeing a DPPI channel group.
* @details This function also disables the chosen group.
*
* @param[in] group DPPI channel group to be freed.
*
* @retval NRFX_SUCCESS The channel group was successfully freed.
* @retval NRFX_ERROR_INVALID_PARAM The specified group is not allocated.
*/
nrfx_err_t nrfx_dppi_group_free(nrf_dppi_channel_group_t group);
/**
* @brief Function for including a DPPI channel in a channel group.
*
* @param[in] channel DPPI channel to be added.
* @param[in] group Channel group in which to include the channel.
*
* @retval NRFX_SUCCESS The channel was successfully included.
* @retval NRFX_ERROR_INVALID_PARAM The specified group or channel is not allocated.
*/
nrfx_err_t nrfx_dppi_channel_include_in_group(uint8_t channel,
nrf_dppi_channel_group_t group);
/**
* @brief Function for removing a DPPI channel from a channel group.
*
* @param[in] channel DPPI channel to be removed.
* @param[in] group Channel group from which to remove the channel.
*
* @retval NRFX_SUCCESS The channel was successfully removed.
* @retval NRFX_ERROR_INVALID_PARAM The specified group or channel is not allocated.
*/
nrfx_err_t nrfx_dppi_channel_remove_from_group(uint8_t channel,
nrf_dppi_channel_group_t group);
/**
* @brief Function for clearing a DPPI channel group.
*
* @param[in] group Channel group to be cleared.
*
* @retval NRFX_SUCCESS The group was successfully cleared.
* @retval NRFX_ERROR_INVALID_PARAM The specified group is not allocated.
*/
nrfx_err_t nrfx_dppi_group_clear(nrf_dppi_channel_group_t group);
/**
* @brief Function for enabling a DPPI channel group.
*
* @param[in] group Channel group to be enabled.
*
* @retval NRFX_SUCCESS The group was successfully enabled.
* @retval NRFX_ERROR_INVALID_PARAM The specified group is not allocated.
*/
nrfx_err_t nrfx_dppi_group_enable(nrf_dppi_channel_group_t group);
/**
* @brief Function for disabling a DPPI channel group.
*
* @param[in] group Channel group to be disabled.
*
* @retval NRFX_SUCCESS The group was successfully disabled.
* @retval NRFX_ERROR_INVALID_PARAM The specified group is not allocated.
*/
nrfx_err_t nrfx_dppi_group_disable(nrf_dppi_channel_group_t group);
/** @} */
#ifdef __cplusplus
}
#endif
#endif // NRFX_DPPI_H__

View file

@ -1,435 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_GPIOTE_H__
#define NRFX_GPIOTE_H__
#include <nrfx.h>
#include <hal/nrf_gpiote.h>
#include <hal/nrf_gpio.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_gpiote GPIOTE driver
* @{
* @ingroup nrf_gpiote
* @brief GPIO Task Event (GPIOTE) peripheral driver.
*/
/** @brief Input pin configuration. */
typedef struct
{
nrf_gpiote_polarity_t sense; /**< Transition that triggers the interrupt. */
nrf_gpio_pin_pull_t pull; /**< Pulling mode. */
bool is_watcher : 1; /**< True when the input pin is tracking an output pin. */
bool hi_accuracy : 1; /**< True when high accuracy (IN_EVENT) is used. */
bool skip_gpio_setup : 1; /**< Do not change GPIO configuration */
} nrfx_gpiote_in_config_t;
/**
* @brief Macro for configuring a pin to use a GPIO IN or PORT EVENT to detect low-to-high transition.
* @details Set hi_accu to true to use IN_EVENT.
*/
#define NRFX_GPIOTE_CONFIG_IN_SENSE_LOTOHI(hi_accu) \
{ \
.sense = NRF_GPIOTE_POLARITY_LOTOHI, \
.pull = NRF_GPIO_PIN_NOPULL, \
.is_watcher = false, \
.hi_accuracy = hi_accu, \
.skip_gpio_setup = false, \
}
/**
* @brief Macro for configuring a pin to use a GPIO IN or PORT EVENT to detect high-to-low transition.
* @details Set hi_accu to true to use IN_EVENT.
*/
#define NRFX_GPIOTE_CONFIG_IN_SENSE_HITOLO(hi_accu) \
{ \
.sense = NRF_GPIOTE_POLARITY_HITOLO, \
.pull = NRF_GPIO_PIN_NOPULL, \
.is_watcher = false, \
.hi_accuracy = hi_accu, \
.skip_gpio_setup = false, \
}
/**
* @brief Macro for configuring a pin to use a GPIO IN or PORT EVENT to detect any change on the pin.
* @details Set hi_accu to true to use IN_EVENT.
*/
#define NRFX_GPIOTE_CONFIG_IN_SENSE_TOGGLE(hi_accu) \
{ \
.sense = NRF_GPIOTE_POLARITY_TOGGLE, \
.pull = NRF_GPIO_PIN_NOPULL, \
.is_watcher = false, \
.hi_accuracy = hi_accu, \
.skip_gpio_setup = false, \
}
/**
* @brief Macro for configuring a pin to use a GPIO IN or PORT EVENT to detect low-to-high transition.
* @details Set hi_accu to true to use IN_EVENT.
* @note This macro prepares configuration that skips the GPIO setup.
*/
#define NRFX_GPIOTE_RAW_CONFIG_IN_SENSE_LOTOHI(hi_accu) \
{ \
.sense = NRF_GPIOTE_POLARITY_LOTOHI, \
.pull = NRF_GPIO_PIN_NOPULL, \
.is_watcher = false, \
.hi_accuracy = hi_accu, \
.skip_gpio_setup = true, \
}
/**
* @brief Macro for configuring a pin to use a GPIO IN or PORT EVENT to detect high-to-low transition.
* @details Set hi_accu to true to use IN_EVENT.
* @note This macro prepares configuration that skips the GPIO setup.
*/
#define NRFX_GPIOTE_RAW_CONFIG_IN_SENSE_HITOLO(hi_accu) \
{ \
.sense = NRF_GPIOTE_POLARITY_HITOLO, \
.pull = NRF_GPIO_PIN_NOPULL, \
.is_watcher = false, \
.hi_accuracy = hi_accu, \
.skip_gpio_setup = true, \
}
/**
* @brief Macro for configuring a pin to use a GPIO IN or PORT EVENT to detect any change on the pin.
* @details Set hi_accu to true to use IN_EVENT.
* @note This macro prepares configuration that skips the GPIO setup.
*/
#define NRFX_GPIOTE_RAW_CONFIG_IN_SENSE_TOGGLE(hi_accu) \
{ \
.sense = NRF_GPIOTE_POLARITY_TOGGLE, \
.pull = NRF_GPIO_PIN_NOPULL, \
.is_watcher = false, \
.hi_accuracy = hi_accu, \
.skip_gpio_setup = true, \
}
/** @brief Output pin configuration. */
typedef struct
{
nrf_gpiote_polarity_t action; /**< Configuration of the pin task. */
nrf_gpiote_outinit_t init_state; /**< Initial state of the output pin. */
bool task_pin; /**< True if the pin is controlled by a GPIOTE task. */
} nrfx_gpiote_out_config_t;
/** @brief Macro for configuring a pin to use as output. GPIOTE is not used for the pin. */
#define NRFX_GPIOTE_CONFIG_OUT_SIMPLE(init_high) \
{ \
.action = NRF_GPIOTE_POLARITY_LOTOHI, \
.init_state = init_high ? NRF_GPIOTE_INITIAL_VALUE_HIGH : NRF_GPIOTE_INITIAL_VALUE_LOW, \
.task_pin = false, \
}
/**
* @brief Macro for configuring a pin to use the GPIO OUT TASK to change the state from high to low.
* @details The task will clear the pin. Therefore, the pin is set initially.
*/
#define NRFX_GPIOTE_CONFIG_OUT_TASK_LOW \
{ \
.init_state = NRF_GPIOTE_INITIAL_VALUE_HIGH, \
.task_pin = true, \
.action = NRF_GPIOTE_POLARITY_HITOLO, \
}
/**
* @brief Macro for configuring a pin to use the GPIO OUT TASK to change the state from low to high.
* @details The task will set the pin. Therefore, the pin is cleared initially.
*/
#define NRFX_GPIOTE_CONFIG_OUT_TASK_HIGH \
{ \
.action = NRF_GPIOTE_POLARITY_LOTOHI, \
.init_state = NRF_GPIOTE_INITIAL_VALUE_LOW, \
.task_pin = true, \
}
/**
* @brief Macro for configuring a pin to use the GPIO OUT TASK to toggle the pin state.
* @details The initial pin state must be provided.
*/
#define NRFX_GPIOTE_CONFIG_OUT_TASK_TOGGLE(init_high) \
{ \
.action = NRF_GPIOTE_POLARITY_TOGGLE, \
.init_state = init_high ? NRF_GPIOTE_INITIAL_VALUE_HIGH : NRF_GPIOTE_INITIAL_VALUE_LOW, \
.task_pin = true, \
}
/** @brief Pin. */
typedef uint32_t nrfx_gpiote_pin_t;
/**
* @brief Pin event handler prototype.
*
* @param[in] pin Pin that triggered this event.
* @param[in] action Action that led to triggering this event.
*/
typedef void (*nrfx_gpiote_evt_handler_t)(nrfx_gpiote_pin_t pin, nrf_gpiote_polarity_t action);
/**
* @brief Function for initializing the GPIOTE module.
*
* @details Only static configuration is supported to prevent the shared
* resource being customized by the initiator.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver was already initialized.
*/
nrfx_err_t nrfx_gpiote_init(void);
/**
* @brief Function for checking if the GPIOTE module is initialized.
*
* @details The GPIOTE module is a shared module. Therefore, check if
* the module is already initialized and skip initialization if it is.
*
* @retval true The module is already initialized.
* @retval false The module is not initialized.
*/
bool nrfx_gpiote_is_init(void);
/** @brief Function for uninitializing the GPIOTE module. */
void nrfx_gpiote_uninit(void);
/**
* @brief Function for initializing a GPIOTE output pin.
* @details The output pin can be controlled by the CPU or by PPI. The initial
* configuration specifies which mode is used. If PPI mode is used, the driver
* attempts to allocate one of the available GPIOTE channels. If no channel is
* available, an error is returned.
*
* @param[in] pin Pin.
* @param[in] p_config Initial configuration.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver is not initialized or the pin is already used.
* @retval NRFX_ERROR_NO_MEM No GPIOTE channel is available.
*/
nrfx_err_t nrfx_gpiote_out_init(nrfx_gpiote_pin_t pin,
nrfx_gpiote_out_config_t const * p_config);
/**
* @brief Function for uninitializing a GPIOTE output pin.
* @details The driver frees the GPIOTE channel if the output pin was using one.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_uninit(nrfx_gpiote_pin_t pin);
/**
* @brief Function for setting a GPIOTE output pin.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_set(nrfx_gpiote_pin_t pin);
/**
* @brief Function for clearing a GPIOTE output pin.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_clear(nrfx_gpiote_pin_t pin);
/**
* @brief Function for toggling a GPIOTE output pin.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_toggle(nrfx_gpiote_pin_t pin);
/**
* @brief Function for enabling a GPIOTE output pin task.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_task_enable(nrfx_gpiote_pin_t pin);
/**
* @brief Function for disabling a GPIOTE output pin task.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_task_disable(nrfx_gpiote_pin_t pin);
/**
* @brief Function for getting the address of a configurable GPIOTE task.
*
* @param[in] pin Pin.
*
* @return Address of OUT task.
*/
uint32_t nrfx_gpiote_out_task_addr_get(nrfx_gpiote_pin_t pin);
#if defined(GPIOTE_FEATURE_SET_PRESENT) || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for getting the address of a configurable GPIOTE task.
*
* @param[in] pin Pin.
*
* @return Address of SET task.
*/
uint32_t nrfx_gpiote_set_task_addr_get(nrfx_gpiote_pin_t pin);
#endif // defined(GPIOTE_FEATURE_SET_PRESENT) || defined(__NRFX_DOXYGEN__)
#if defined(GPIOTE_FEATURE_CLR_PRESENT) || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for getting the address of a configurable GPIOTE task.
*
* @param[in] pin Pin.
*
* @return Address of CLR task.
*/
uint32_t nrfx_gpiote_clr_task_addr_get(nrfx_gpiote_pin_t pin);
#endif // defined(GPIOTE_FEATURE_CLR_PRESENT) || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for initializing a GPIOTE input pin.
* @details The input pin can act in two ways:
* - lower accuracy but low power (high frequency clock not needed)
* - higher accuracy (high frequency clock required)
*
* The initial configuration specifies which mode is used.
* If high-accuracy mode is used, the driver attempts to allocate one
* of the available GPIOTE channels. If no channel is
* available, an error is returned.
* In low accuracy mode SENSE feature is used. In this case, only one active pin
* can be detected at a time. It can be worked around by setting all of the used
* low accuracy pins to toggle mode.
* For more information about SENSE functionality, refer to Product Specification.
*
* @param[in] pin Pin.
* @param[in] p_config Initial configuration.
* @param[in] evt_handler User function to be called when the configured transition occurs.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver is not initialized or the pin is already used.
* @retval NRFX_ERROR_NO_MEM No GPIOTE channel is available.
*/
nrfx_err_t nrfx_gpiote_in_init(nrfx_gpiote_pin_t pin,
nrfx_gpiote_in_config_t const * p_config,
nrfx_gpiote_evt_handler_t evt_handler);
/**
* @brief Function for uninitializing a GPIOTE input pin.
* @details The driver frees the GPIOTE channel if the input pin was using one.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_in_uninit(nrfx_gpiote_pin_t pin);
/**
* @brief Function for enabling sensing of a GPIOTE input pin.
*
* @details If the input pin is configured as high-accuracy pin, the function
* enables an IN_EVENT. Otherwise, the function enables the GPIO sense mechanism.
* The PORT event is shared between multiple pins, therefore the interrupt is always enabled.
*
* @param[in] pin Pin.
* @param[in] int_enable True to enable the interrupt. Always valid for a high-accuracy pin.
*/
void nrfx_gpiote_in_event_enable(nrfx_gpiote_pin_t pin, bool int_enable);
/**
* @brief Function for disabling a GPIOTE input pin.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_in_event_disable(nrfx_gpiote_pin_t pin);
/**
* @brief Function for checking if a GPIOTE input pin is set.
*
* @param[in] pin Pin.
*
* @retval true The input pin is set.
* @retval false The input pin is not set.
*/
bool nrfx_gpiote_in_is_set(nrfx_gpiote_pin_t pin);
/**
* @brief Function for getting the address of a GPIOTE input pin event.
* @details If the pin is configured to use low-accuracy mode, the address of the PORT event is returned.
*
* @param[in] pin Pin.
*
* @return Address of the specified input pin event.
*/
uint32_t nrfx_gpiote_in_event_addr_get(nrfx_gpiote_pin_t pin);
/**
* @brief Function for forcing a specific state on the pin configured as task.
*
* @param[in] pin Pin.
* @param[in] state Pin state.
*/
void nrfx_gpiote_out_task_force(nrfx_gpiote_pin_t pin, uint8_t state);
/**
* @brief Function for triggering the task OUT manually.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_out_task_trigger(nrfx_gpiote_pin_t pin);
#if defined(GPIOTE_FEATURE_SET_PRESENT) || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for triggering the task SET manually.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_set_task_trigger(nrfx_gpiote_pin_t pin);
#endif // defined(GPIOTE_FEATURE_SET_PRESENT) || defined(__NRFX_DOXYGEN__)
#if defined(GPIOTE_FEATURE_CLR_PRESENT) || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for triggering the task CLR manually.
*
* @param[in] pin Pin.
*/
void nrfx_gpiote_clr_task_trigger(nrfx_gpiote_pin_t pin);
#endif // defined(GPIOTE_FEATURE_CLR_PRESENT) || defined(__NRFX_DOXYGEN__)
/** @} */
void nrfx_gpiote_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_GPIOTE_H__

View file

@ -1,244 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_I2S_H__
#define NRFX_I2S_H__
#include <nrfx.h>
#include <hal/nrf_i2s.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_i2s I2S driver
* @{
* @ingroup nrf_i2s
* @brief Inter-IC Sound (I2S) peripheral driver.
*/
/**
* @brief This value can be provided instead of a pin number for the signals
* SDOUT, SDIN, and MCK to specify that a given signal is not used
* and therefore does not need to be connected to a pin.
*/
#define NRFX_I2S_PIN_NOT_USED 0xFF
/** @brief I2S driver configuration structure. */
typedef struct
{
uint8_t sck_pin; ///< SCK pin number.
uint8_t lrck_pin; ///< LRCK pin number.
uint8_t mck_pin; ///< MCK pin number.
/**< Optional. Use @ref NRFX_I2S_PIN_NOT_USED
* if this signal is not needed. */
uint8_t sdout_pin; ///< SDOUT pin number.
/**< Optional. Use @ref NRFX_I2S_PIN_NOT_USED
* if this signal is not needed. */
uint8_t sdin_pin; ///< SDIN pin number.
/**< Optional. Use @ref NRFX_I2S_PIN_NOT_USED
* if this signal is not needed. */
uint8_t irq_priority; ///< Interrupt priority.
nrf_i2s_mode_t mode; ///< Mode of operation.
nrf_i2s_format_t format; ///< Frame format.
nrf_i2s_align_t alignment; ///< Alignment of sample within a frame.
nrf_i2s_swidth_t sample_width; ///< Sample width.
nrf_i2s_channels_t channels; ///< Enabled channels.
nrf_i2s_mck_t mck_setup; ///< Master clock setup.
nrf_i2s_ratio_t ratio; ///< MCK/LRCK ratio.
} nrfx_i2s_config_t;
/** @brief I2S driver buffers structure. */
typedef struct
{
uint32_t * p_rx_buffer; ///< Pointer to the buffer for received data.
uint32_t const * p_tx_buffer; ///< Pointer to the buffer with data to be sent.
} nrfx_i2s_buffers_t;
/** @brief I2S driver default configuration. */
#define NRFX_I2S_DEFAULT_CONFIG \
{ \
.sck_pin = NRFX_I2S_CONFIG_SCK_PIN, \
.lrck_pin = NRFX_I2S_CONFIG_LRCK_PIN, \
.mck_pin = NRFX_I2S_CONFIG_MCK_PIN, \
.sdout_pin = NRFX_I2S_CONFIG_SDOUT_PIN, \
.sdin_pin = NRFX_I2S_CONFIG_SDIN_PIN, \
.irq_priority = NRFX_I2S_CONFIG_IRQ_PRIORITY, \
.mode = (nrf_i2s_mode_t)NRFX_I2S_CONFIG_MASTER, \
.format = (nrf_i2s_format_t)NRFX_I2S_CONFIG_FORMAT, \
.alignment = (nrf_i2s_align_t)NRFX_I2S_CONFIG_ALIGN, \
.sample_width = (nrf_i2s_swidth_t)NRFX_I2S_CONFIG_SWIDTH, \
.channels = (nrf_i2s_channels_t)NRFX_I2S_CONFIG_CHANNELS, \
.mck_setup = (nrf_i2s_mck_t)NRFX_I2S_CONFIG_MCK_SETUP, \
.ratio = (nrf_i2s_ratio_t)NRFX_I2S_CONFIG_RATIO, \
}
#define NRFX_I2S_STATUS_NEXT_BUFFERS_NEEDED (1UL << 0)
/**< The application must provide buffers that are to be used in the next
* part of the transfer. A call to @ref nrfx_i2s_next_buffers_set must
* be done before the currently used buffers are completely processed
* (that is, the time remaining for supplying the next buffers depends on
* the used size of the buffers). */
/**
* @brief I2S driver data handler type.
*
* A data handling function of this type must be specified during the initialization
* of the driver. The driver will call this function when it finishes using
* buffers passed to it by the application, and when it needs to be provided
* with buffers for the next part of the transfer.
*
* @note The @c p_released pointer passed to this function is temporary and
* will be invalid after the function returns, hence it cannot be stored
* and used later. If needed, the pointed content (that is, buffers pointers)
* must be copied instead.
*
* @param[in] p_released Pointer to a structure with pointers to buffers
* passed previously to the driver that will no longer
* be accessed by it (they can be now safely released or
* used for another purpose, in particular for a next
* part of the transfer).
* This pointer will be NULL if the application did not
* supply the buffers for the next part of the transfer
* (via a call to @ref nrfx_i2s_next_buffers_set) since
* the previous time the data handler signaled such need.
* This means that data corruption occurred (the previous
* buffers are used for the second time) and no buffers
* can be released at the moment.
* Both pointers in this structure are NULL when the
* handler is called for the first time after a transfer
* is started, because no data has been transferred yet
* at this point. In all successive calls the pointers
* specify what has been sent (TX) and what has been
* received (RX) in the part of transfer that has just
* been completed (provided that a given direction is
* enabled, see @ref nrfx_i2s_start).
* @param[in] status Bit field describing the current status of the transfer.
* It can be 0 or a combination of the following flags:
* - @ref NRFX_I2S_STATUS_NEXT_BUFFERS_NEEDED
*/
typedef void (* nrfx_i2s_data_handler_t)(nrfx_i2s_buffers_t const * p_released,
uint32_t status);
/**
* @brief Function for initializing the I2S driver.
*
* @param[in] p_config Pointer to the structure with the initial configuration.
* @param[in] handler Data handler provided by the user. Must not be NULL.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver was already initialized.
* @retval NRFX_ERROR_INVALID_PARAM The requested combination of configuration
* options is not allowed by the I2S peripheral.
*/
nrfx_err_t nrfx_i2s_init(nrfx_i2s_config_t const * p_config,
nrfx_i2s_data_handler_t handler);
/** @brief Function for uninitializing the I2S driver. */
void nrfx_i2s_uninit(void);
/**
* @brief Function for starting the continuous I2S transfer.
*
* The I2S data transfer can be performed in one of three modes: RX (reception)
* only, TX (transmission) only, or in both directions simultaneously.
* The mode is selected by specifying a proper buffer for a given direction
* in the call to this function or by passing NULL instead if this direction
* is to be disabled.
*
* The length of the buffer (which is a common value for RX and TX if both
* directions are enabled) is specified in 32-bit words. One 32-bit memory
* word can either contain four 8-bit samples, two 16-bit samples, or one
* right-aligned 24-bit sample sign-extended to a 32-bit value.
* For a detailed memory mapping for different supported configurations,
* see the @linkProductSpecification52.
*
* @note Peripherals using EasyDMA (including I2S) require the transfer buffers
* to be placed in the Data RAM region. If this condition is not met,
* this function will fail with the error code NRFX_ERROR_INVALID_ADDR.
*
* @param[in] p_initial_buffers Pointer to a structure specifying the buffers
* to be used in the initial part of the transfer
* (buffers for all consecutive parts are provided
* through the data handler).
* @param[in] buffer_size Size of the buffers (in 32-bit words).
* Must not be 0.
* @param[in] flags Transfer options (0 for default settings).
* Currently, no additional flags are available.
*
* @retval NRFX_SUCCESS The operation was successful.
* @retval NRFX_ERROR_INVALID_STATE Transfer was already started or
* the driver has not been initialized.
* @retval NRFX_ERROR_INVALID_ADDR The provided buffers are not placed
* in the Data RAM region.
*/
nrfx_err_t nrfx_i2s_start(nrfx_i2s_buffers_t const * p_initial_buffers,
uint16_t buffer_size,
uint8_t flags);
/**
* @brief Function for supplying the buffers to be used in the next part of
* the transfer.
*
* The application must call this function when the data handler receives
* @ref NRFX_I2S_STATUS_NEXT_BUFFERS_NEEDED in the @c status parameter.
* The call can be done immediately from the data handler function or later,
* but it has to be done before the I2S peripheral finishes processing the
* buffers supplied previously. Otherwise, data corruption will occur.
*
* @sa nrfx_i2s_data_handler_t
*
* @retval NRFX_SUCCESS If the operation was successful.
* @retval NRFX_ERROR_INVALID_STATE If the buffers were already supplied or
* the peripheral is currently being stopped.
*/
nrfx_err_t nrfx_i2s_next_buffers_set(nrfx_i2s_buffers_t const * p_buffers);
/** @brief Function for stopping the I2S transfer. */
void nrfx_i2s_stop(void);
/** @} */
void nrfx_i2s_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_I2S_H__

View file

@ -1,144 +0,0 @@
/*
* Copyright (c) 2014 - 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_LPCOMP_H__
#define NRFX_LPCOMP_H__
#include <nrfx.h>
#include <hal/nrf_lpcomp.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_lpcomp LPCOMP driver
* @{
* @ingroup nrf_lpcomp
* @brief Low Power Comparator (LPCOMP) peripheral driver.
*/
/**
* @brief LPCOMP event handler function type.
* @param[in] event LPCOMP event.
*/
typedef void (* nrfx_lpcomp_event_handler_t)(nrf_lpcomp_event_t event);
/** @brief LPCOMP configuration. */
typedef struct
{
nrf_lpcomp_config_t hal; /**< LPCOMP HAL configuration. */
nrf_lpcomp_input_t input; /**< Input to be monitored. */
uint8_t interrupt_priority; /**< LPCOMP interrupt priority. */
} nrfx_lpcomp_config_t;
/** @brief LPCOMP driver default configuration, including the LPCOMP HAL configuration. */
#ifdef NRF52_SERIES
#define NRFX_LPCOMP_DEFAULT_CONFIG \
{ \
.hal = { (nrf_lpcomp_ref_t)NRFX_LPCOMP_CONFIG_REFERENCE , \
(nrf_lpcomp_detect_t)NRFX_LPCOMP_CONFIG_DETECTION, \
(nrf_lpcomp_hysteresis_t)NRFX_LPCOMP_CONFIG_HYST }, \
.input = (nrf_lpcomp_input_t)NRFX_LPCOMP_CONFIG_INPUT, \
.interrupt_priority = NRFX_LPCOMP_CONFIG_IRQ_PRIORITY \
}
#else
#define NRFX_LPCOMP_DEFAULT_CONFIG \
{ \
.hal = { (nrf_lpcomp_ref_t)NRFX_LPCOMP_CONFIG_REFERENCE , \
(nrf_lpcomp_detect_t)NRFX_LPCOMP_CONFIG_DETECTION }, \
.input = (nrf_lpcomp_input_t)NRFX_LPCOMP_CONFIG_INPUT, \
.interrupt_priority = NRFX_LPCOMP_CONFIG_IRQ_PRIORITY \
}
#endif
/**
* @brief Function for initializing the LPCOMP driver.
*
* This function initializes the LPCOMP driver, but does not enable the peripheral or any interrupts.
* To start the driver, call the function nrfx_lpcomp_enable() after initialization.
*
* @param[in] p_config Pointer to the structure with the initial configuration.
* @param[in] event_handler Event handler provided by the user.
* Must not be NULL.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver has already been initialized.
* @retval NRFX_ERROR_BUSY The COMP peripheral is already in use.
* This is possible only if @ref nrfx_prs module
* is enabled.
*/
nrfx_err_t nrfx_lpcomp_init(nrfx_lpcomp_config_t const * p_config,
nrfx_lpcomp_event_handler_t event_handler);
/**
* @brief Function for uninitializing the LCOMP driver.
*
* This function uninitializes the LPCOMP driver. The LPCOMP peripheral and
* its interrupts are disabled, and local variables are cleaned. After this call, you must
* initialize the driver again by calling nrfx_lpcomp_init() if you want to use it.
*
* @sa nrfx_lpcomp_disable
* @sa nrfx_lpcomp_init
*/
void nrfx_lpcomp_uninit(void);
/**
* @brief Function for enabling the LPCOMP peripheral and interrupts.
*
* Before calling this function, the driver must be initialized. This function
* enables the LPCOMP peripheral and its interrupts.
*
* @sa nrfx_lpcomp_disable
*/
void nrfx_lpcomp_enable(void);
/**
* @brief Function for disabling the LPCOMP peripheral.
*
* Before calling this function, the driver must be initialized. This function disables the LPCOMP
* peripheral and its interrupts.
*
* @sa nrfx_lpcomp_enable
*/
void nrfx_lpcomp_disable(void);
/** @} */
void nrfx_lpcomp_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_LPCOMP_H__

View file

@ -1,344 +0,0 @@
/*
* Copyright (c) 2018 - 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_NFCT_H__
#define NRFX_NFCT_H__
#include <nrfx.h>
#include <hal/nrf_nfct.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_nfct NFCT driver
* @{
* @ingroup nrf_nfct
* @brief Near Field Communication Tag (NFCT) peripheral driver.
*/
#define NRFX_NFCT_NFCID1_SINGLE_SIZE 4u ///< Length of single-size NFCID1.
#define NRFX_NFCT_NFCID1_DOUBLE_SIZE 7u ///< Length of double-size NFCID1.
#define NRFX_NFCT_NFCID1_TRIPLE_SIZE 10u ///< Length of triple-size NFCID1.
#define NRFX_NFCT_NFCID1_DEFAULT_LEN NRFX_NFCT_NFCID1_DOUBLE_SIZE ///< Default length of NFC ID. */
/** @brief NFCT hardware states. */
typedef enum
{
NRFX_NFCT_STATE_DISABLED = NRF_NFCT_TASK_DISABLE, ///< NFC Tag is disabled (no sensing of an external NFC field).
NRFX_NFCT_STATE_SENSING = NRF_NFCT_TASK_SENSE, ///< NFC Tag is sensing whether there is an external NFC field.
NRFX_NFCT_STATE_ACTIVATED = NRF_NFCT_TASK_ACTIVATE, ///< NFC Tag is powered-up (see @ref nrfx_nfct_active_state_t for possible substates).
} nrfx_nfct_state_t;
/**
* @brief NFC tag states, when NFCT hardware is activated.
*
* @details These states are substates of the @ref NRFX_NFCT_STATE_ACTIVATED state.
*/
typedef enum
{
NRFX_NFCT_ACTIVE_STATE_IDLE = NRF_NFCT_TASK_GOIDLE, ///< NFC Tag is activated and idle (not selected by a reader).
NRFX_NFCT_ACTIVE_STATE_SLEEP = NRF_NFCT_TASK_GOSLEEP, ///< NFC Tag is sleeping.
NRFX_NFCT_ACTIVE_STATE_DEFAULT, ///< NFC Tag is either sleeping or idle, depending on the previous state before being selected by a poller.
} nrfx_nfct_active_state_t;
/**
* @brief NFCT driver event types, passed to the upper-layer callback function
* provided during the initialization.
*/
typedef enum
{
NRFX_NFCT_EVT_FIELD_DETECTED = NRF_NFCT_INT_FIELDDETECTED_MASK, ///< External NFC field is detected.
NRFX_NFCT_EVT_FIELD_LOST = NRF_NFCT_INT_FIELDLOST_MASK, ///< External NFC Field is lost.
NRFX_NFCT_EVT_SELECTED = NRF_NFCT_INT_SELECTED_MASK, ///< Tag was selected by the poller.
NRFX_NFCT_EVT_RX_FRAMESTART = NRF_NFCT_INT_RXFRAMESTART_MASK, ///< Data frame reception started.
NRFX_NFCT_EVT_RX_FRAMEEND = NRF_NFCT_INT_RXFRAMEEND_MASK, ///< Data frame is received.
NRFX_NFCT_EVT_TX_FRAMESTART = NRF_NFCT_INT_TXFRAMESTART_MASK, ///< Data frame transmission started.
NRFX_NFCT_EVT_TX_FRAMEEND = NRF_NFCT_INT_TXFRAMEEND_MASK, ///< Data frame is transmitted.
NRFX_NFCT_EVT_ERROR = NRF_NFCT_INT_ERROR_MASK, ///< Error occurred in an NFC communication.
} nrfx_nfct_evt_id_t;
/** @brief NFCT timing-related error types. */
typedef enum
{
NRFX_NFCT_ERROR_FRAMEDELAYTIMEOUT, ///< No response frame was transmitted to the poller in the transmit window.
NRFX_NFCT_ERROR_NUM, ///< Total number of possible errors.
} nrfx_nfct_error_t;
/** @brief NFCT driver parameter types. */
typedef enum
{
NRFX_NFCT_PARAM_ID_FDT, ///< NFC-A Frame Delay Time parameter.
NRFX_NFCT_PARAM_ID_SEL_RES, ///< Value of the 'Protocol' field in the NFC-A SEL_RES frame.
NRFX_NFCT_PARAM_ID_NFCID1, ///< NFC-A NFCID1 setting (NFC tag identifier).
} nrfx_nfct_param_id_t;
/** @brief NFCID1 descriptor. */
typedef struct
{
uint8_t const * p_id; ///< NFCID1 data.
uint8_t id_size; ///< NFCID1 size.
} nrfx_nfct_nfcid1_t;
/** @brief NFCT driver parameter descriptor. */
typedef struct
{
nrfx_nfct_param_id_t id; ///< Type of parameter.
union
{
uint32_t fdt; ///< NFC-A Frame Delay Time. Filled when nrfx_nfct_param_t::id is @ref NRFX_NFCT_PARAM_ID_FDT.
uint8_t sel_res_protocol; ///< NFC-A value of the 'Protocol' field in the SEL_RES frame. Filled when nrfx_nfct_param_t::id is @ref NRFX_NFCT_PARAM_ID_SEL_RES.
nrfx_nfct_nfcid1_t nfcid1; ///< NFC-A NFCID1 value (tag identifier). Filled when nrfx_nfct_param_t::id is @ref NRFX_NFCT_PARAM_ID_NFCID1.
} data; ///< Union to store parameter data.
} nrfx_nfct_param_t;
/** @brief NFCT driver RX/TX buffer descriptor. */
typedef struct
{
uint32_t data_size; ///< RX/TX buffer size.
uint8_t const * p_data; ///< RX/TX buffer.
} nrfx_nfct_data_desc_t;
/** @brief Structure used to describe the @ref NRFX_NFCT_EVT_RX_FRAMEEND event type. */
typedef struct
{
uint32_t rx_status; ///< RX error status.
nrfx_nfct_data_desc_t rx_data; ///< RX buffer.
} nrfx_nfct_evt_rx_frameend_t;
/** @brief Structure used to describe the @ref NRFX_NFCT_EVT_TX_FRAMESTART event type. */
typedef struct
{
nrfx_nfct_data_desc_t tx_data; ///< TX buffer.
} nrfx_nfct_evt_tx_framestart_t;
/** @brief Structure used to describe the @ref NRFX_NFCT_EVT_ERROR event type. */
typedef struct
{
nrfx_nfct_error_t reason; ///< Reason for error.
} nrfx_nfct_evt_error_t;
/** @brief NFCT driver event. */
typedef struct
{
nrfx_nfct_evt_id_t evt_id; ///< Type of event.
union
{
nrfx_nfct_evt_rx_frameend_t rx_frameend; ///< End of the RX frame data. Filled when nrfx_nfct_evt_t::evt_id is @ref NRFX_NFCT_EVT_RX_FRAMEEND.
nrfx_nfct_evt_tx_framestart_t tx_framestart; ///< Start of the TX frame data. Filled when nrfx_nfct_evt_t::evt_id is @ref NRFX_NFCT_EVT_TX_FRAMESTART.
nrfx_nfct_evt_error_t error; ///< Error data. Filled when nrfx_nfct_evt_t::evt_id is @ref NRFX_NFCT_EVT_ERROR.
} params; ///< Union to store event data.
} nrfx_nfct_evt_t;
/**
* @brief Callback descriptor to pass events from the NFCT driver to the upper layer.
*
* @param[in] p_event Pointer to the event descriptor.
*/
typedef void (*nrfx_nfct_handler_t)(nrfx_nfct_evt_t const * p_event);
/** @brief NFCT driver configuration structure. */
typedef struct
{
uint32_t rxtx_int_mask; ///< Mask for enabling RX/TX events. Indicate which events must be forwarded to the upper layer by using @ref nrfx_nfct_evt_id_t. By default, no events are enabled. */
nrfx_nfct_handler_t cb; ///< Callback.
} nrfx_nfct_config_t;
/**
* @brief Function for initializing the NFCT driver.
*
* @param[in] p_config Pointer to the NFCT driver configuration structure.
*
* @retval NRFX_SUCCESS The NFCT driver was initialized successfully.
* @retval NRFX_ERROR_INVALID_STATE The NFCT driver is already initialized.
*/
nrfx_err_t nrfx_nfct_init(nrfx_nfct_config_t const * p_config);
/**
* @brief Function for uninitializing the NFCT driver.
*
* After uninitialization, the instance is in disabled state.
*/
void nrfx_nfct_uninit(void);
/**
* @brief Function for starting the NFC subsystem.
*
* After this function completes, NFC readers are able to detect the tag.
*/
void nrfx_nfct_enable(void);
/**
* @brief Function for disabling the NFCT driver.
*
* After this function returns, NFC readers are no longer able to connect
* to the tag.
*/
void nrfx_nfct_disable(void);
/**
* @brief Function for checking whether the external NFC field is present in the range of the tag.
*
* @retval true The NFC field is present.
* @retval false No NFC field is present.
*/
bool nrfx_nfct_field_check(void);
/**
* @brief Function for preparing the NFCT driver for receiving an NFC frame.
*
* @param[in] p_rx_data Pointer to the RX buffer.
*/
void nrfx_nfct_rx(nrfx_nfct_data_desc_t const * p_rx_data);
/**
* @brief Function for transmitting an NFC frame.
*
* @param[in] p_tx_data Pointer to the TX buffer.
* @param[in] delay_mode Delay mode of the NFCT frame timer.
*
* @retval NRFX_SUCCESS The operation was successful.
* @retval NRFX_ERROR_INVALID_LENGTH The TX buffer size is invalid.
*/
nrfx_err_t nrfx_nfct_tx(nrfx_nfct_data_desc_t const * p_tx_data,
nrf_nfct_frame_delay_mode_t delay_mode);
/**
* @brief Function for moving the NFCT to a new state.
*
* @note The HFCLK must be running before activating the NFCT with
* @ref NRFX_NFCT_STATE_ACTIVATED.
*
* @param[in] state The required state.
*/
void nrfx_nfct_state_force(nrfx_nfct_state_t state);
/**
* @brief Function for moving the NFCT to a new initial substate within @ref NRFX_NFCT_STATE_ACTIVATED.
*
* @param[in] sub_state The required substate.
*/
void nrfx_nfct_init_substate_force(nrfx_nfct_active_state_t sub_state);
/**
* @brief Function for setting the NFC communication parameter.
*
* @note Parameter validation for length and acceptable values.
*
* @param[in] p_param Pointer to parameter descriptor.
*
* @retval NRFX_SUCCESS The operation was successful.
* @retval NRFX_ERROR_INVALID_PARAM The parameter data is invalid.
*/
nrfx_err_t nrfx_nfct_parameter_set(nrfx_nfct_param_t const * p_param);
/**
* @brief Function for getting default bytes for NFCID1.
*
* @param[in,out] p_nfcid1_buff In: empty buffer for data;
* Out: buffer with the NFCID1 default data. These values
* can be used to fill the Type 2 Tag Internal Bytes.
* @param[in] nfcid1_buff_len Length of the NFCID1 buffer.
*
* @retval NRFX_SUCCESS The operation was successful.
* @retval NRFX_ERROR_INVALID_LENGTH Length of the NFCID buffer is different than
* @ref NRFX_NFCT_NFCID1_SINGLE_SIZE,
* @ref NRFX_NFCT_NFCID1_DOUBLE_SIZE, or
* @ref NRFX_NFCT_NFCID1_TRIPLE_SIZE.
*/
nrfx_err_t nrfx_nfct_nfcid1_default_bytes_get(uint8_t * const p_nfcid1_buff,
uint32_t nfcid1_buff_len);
/**
* @brief Function for enabling the automatic collision resolution.
*
* @details As defined by the NFC Forum Digital Protocol Technical Specification (and ISO 14443-3),
* the automatic collision resolution is implemented in the NFCT hardware.
* This function allows enabling and disabling this feature.
*/
void nrfx_nfct_autocolres_enable(void);
/**
* @brief Function for disabling the automatic collision resolution.
*
* @details See also details in @ref nrfx_nfct_autocolres_enable.
*/
void nrfx_nfct_autocolres_disable(void);
/** @} */
void nrfx_nfct_irq_handler(void);
#ifdef __cplusplus
}
#endif
/**
* @defgroup nrfx_nfct_fixes NFCT driver fixes and workarounds
* @{
* @ingroup nrf_nfct
* @brief Fixes for hardware-related anomalies.
*
* If you are using the nRF52832 chip, the workarounds for the following anomalies are applied:
* - 79. NFCT: A false EVENTS_FIELDDETECTED event occurs after the field is lost.
* - 116. NFCT does not release HFCLK when switching from ACTIVATED to SENSE mode.
* To implement the first workaround, an instance of NRF_TIMER is used. After the NFC field is detected,
* the timing module periodically polls its state to determine when the field is turned off.
* To implement the second workaround, power reset is used to release the clock acquired by NFCT
* after the field is turned off. Note that the NFCT register configuration is restored to defaults.
*
* If you are using the nRF52840 chip, rev. Engineering A, the workarounds for the following anomalies
* are applied:
* - 98. NFCT: The NFCT is not able to communicate with the peer.
* - 116. NFCT does not release HFCLK when switching from ACTIVATED to SENSE mode.
* - 144. NFCT: Not optimal NFC performance
*
* If you are using the nRF52840 chip, rev. 1, or rev. Engineering B or C, the workarounds for the following
* anomalies are applied:
* - 190. NFCT: Event FIELDDETECTED can be generated too early.
* To implement this workaround, an instance of NRF_TIMER is used. After the NFC field is detected,
* the timing module measures the necessary waiting period after which NFCT can be activated.
* This debouncing technique is used to filter possible field instabilities.
*
* The application of the implemented workarounds for the nRF52840 chip is determined at runtime and depends
* on the chip variant.
*
* The current code contains a patch for the anomaly 25 (NFCT: Reset value of
* SENSRES register is incorrect), so that the module now works on Windows Phone.
* @}
*/
#endif // NRFX_NFCT_H__

View file

@ -1,281 +0,0 @@
/*
* Copyright (c) 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_NVMC_H__
#define NRFX_NVMC_H__
#include <nrfx.h>
#include <hal/nrf_nvmc.h>
#include <hal/nrf_ficr.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_nvmc NVMC driver
* @{
* @ingroup nrf_nvmc
* @brief Non-Volatile Memory Controller (NVMC) peripheral driver.
*/
/**
* @brief Function for erasing a page in flash.
*
* This function blocks until the erase operation finishes.
*
* @note Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @param address Address of the first word in the page to erase.
*
* @retval NRFX_SUCCESS Page erase complete.
* @retval NRFX_ERROR_INVALID_ADDR Address is not aligned to the size of the page.
*/
nrfx_err_t nrfx_nvmc_page_erase(uint32_t address);
/**
* @brief Function for erasing the user information configuration register (UICR).
*
* @note Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @retval NRFX_SUCCESS UICR has been successfully erased.
* @retval NRFX_ERROR_NOT_SUPPORTED UICR erase is not supported.
*/
nrfx_err_t nrfx_nvmc_uicr_erase(void);
/**
* @brief Function for erasing the whole flash memory.
*
* @note All user code and UICR will be erased.
*/
void nrfx_nvmc_all_erase(void);
#if defined(NRF_NVMC_PARTIAL_ERASE_PRESENT)
/**
* @brief Function for initiating a complete page erase split into parts (also known as partial erase).
*
* This function initiates a partial erase with the specified duration.
* To execute each part of the partial erase, use @ref nrfx_nvmc_page_partial_erase_continue.
*
* @param address Address of the first word in the page to erase.
* @param duration_ms Time in milliseconds that each partial erase will take.
*
* @retval NRFX_SUCCESS Partial erase started.
* @retval NRFX_ERROR_INVALID_ADDR Address is not aligned to the size of the page.
*
* @sa nrfx_nvmc_page_partial_erase_continue()
*/
nrfx_err_t nrfx_nvmc_page_partial_erase_init(uint32_t address, uint32_t duration_ms);
/**
* @brief Function for performing a part of the complete page erase (also known as partial erase).
*
* Each part takes the amount of time specified during the initialization.
* This function must be called several times to erase the whole page, once for each erase part.
*
* @note Using a page that was not completely erased leads to undefined behavior.
* Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @retval true Partial erase finished.
* @retval false Partial erase not finished.
* Call the function again to process the next part.
*/
bool nrfx_nvmc_page_partial_erase_continue(void);
#endif // defined(NRF_NVMC_PARTIAL_ERASE_PRESENT)
/**
* @brief Function for checking whether a byte is writable at the specified address.
*
* The NVMC is only able to write '0' to bits in the flash that are erased (set to '1').
* It cannot rewrite a bit back to '1'. This function checks if the value currently
* residing at the specified address can be transformed to the desired value
* without any '0' to '1' transitions.
*
* @param address Address to be checked.
* @param value Value to be checked.
*
* @retval true Byte can be written at the specified address.
* @retval false Byte cannot be written at the specified address.
* Erase the page or change the address.
*/
bool nrfx_nvmc_byte_writable_check(uint32_t address, uint8_t value);
/**
* @brief Function for writing a single byte to flash.
*
* To determine if the flash write has been completed, use @ref nrfx_nvmc_write_done_check().
*
* @note Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @param address Address to write to.
* @param value Value to write.
*/
void nrfx_nvmc_byte_write(uint32_t address, uint8_t value);
/**
* @brief Function for checking whether a word is writable at the specified address.
*
* The NVMC is only able to write '0' to bits in the Flash that are erased (set to '1').
* It cannot rewrite a bit back to '1'. This function checks if the value currently
* residing at the specified address can be transformed to the desired value
* without any '0' to '1' transitions.
*
* @param address Address to be checked. Must be word-aligned.
* @param value Value to be checked.
*
* @retval true Word can be written at the specified address.
* @retval false Word cannot be written at the specified address.
* Erase page or change address.
*/
bool nrfx_nvmc_word_writable_check(uint32_t address, uint32_t value);
/**
* @brief Function for writing a 32-bit word to flash.
*
* To determine if the flash write has been completed, use @ref nrfx_nvmc_write_done_check().
*
* @note Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @param address Address to write to. Must be word-aligned.
* @param value Value to write.
*/
void nrfx_nvmc_word_write(uint32_t address, uint32_t value);
/**
* @brief Function for writing consecutive bytes to flash.
*
* To determine if the last flash write has been completed, use @ref nrfx_nvmc_write_done_check().
*
* @note Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @param address Address to write to.
* @param src Pointer to the data to copy from.
* @param num_bytes Number of bytes to write.
*/
void nrfx_nvmc_bytes_write(uint32_t address, void const * src, uint32_t num_bytes);
/**
* @brief Function for writing consecutive words to flash.
*
* To determine if the last flash write has been completed, use @ref nrfx_nvmc_write_done_check().
*
* @note Depending on the source of the code being executed,
* the CPU may be halted during the operation.
* Refer to the Product Specification for more information.
*
* @param address Address to write to. Must be word-aligned.
* @param src Pointer to data to copy from. Must be word-aligned.
* @param num_words Number of words to write.
*/
void nrfx_nvmc_words_write(uint32_t address, void const * src, uint32_t num_words);
/**
* @brief Function for getting the total flash size in bytes.
*
* @return Flash total size in bytes.
*/
uint32_t nrfx_nvmc_flash_size_get(void);
/**
* @brief Function for getting the flash page size in bytes.
*
* @return Flash page size in bytes.
*/
uint32_t nrfx_nvmc_flash_page_size_get(void);
/**
* @brief Function for getting the flash page count.
*
* @return Flash page count.
*/
uint32_t nrfx_nvmc_flash_page_count_get(void);
/**
* @brief Function for checking if the last flash write has been completed.
*
* @retval true Last write completed successfully.
* @retval false Last write is still in progress.
*/
__STATIC_INLINE bool nrfx_nvmc_write_done_check(void);
#if defined(NRF_NVMC_ICACHE_PRESENT)
/**
* @brief Function for enabling the Instruction Cache (ICache).
*
* Enabling ICache reduces the amount of accesses to flash memory,
* which can boost performance and lower power consumption.
*/
__STATIC_INLINE void nrfx_nvmc_icache_enable(void);
/** @brief Function for disabling ICache. */
__STATIC_INLINE void nrfx_nvmc_icache_disable(void);
#endif // defined(NRF_NVMC_ICACHE_PRESENT)
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE bool nrfx_nvmc_write_done_check(void)
{
return nrf_nvmc_ready_check(NRF_NVMC);
}
#if defined(NRF_NVMC_ICACHE_PRESENT)
__STATIC_INLINE void nrfx_nvmc_icache_enable(void)
{
nrf_nvmc_icache_config_set(NRF_NVMC, NRF_NVMC_ICACHE_ENABLE_WITH_PROFILING);
}
__STATIC_INLINE void nrfx_nvmc_icache_disable(void)
{
nrf_nvmc_icache_config_set(NRF_NVMC, NRF_NVMC_ICACHE_DISABLE);
}
#endif // defined(NRF_NVMC_ICACHE_PRESENT)
#endif // SUPPRESS_INLINE_IMPLEMENTATION
/** @} */
#ifdef __cplusplus
}
#endif
#endif // NRF_NVMC_H__

View file

@ -1,198 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_PDM_H__
#define NRFX_PDM_H__
#include <nrfx.h>
#include <hal/nrf_pdm.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_pdm PDM driver
* @{
* @ingroup nrf_pdm
* @brief Pulse Density Modulation (PDM) peripheral driver.
*/
/** @brief Maximum supported PDM buffer size. */
#define NRFX_PDM_MAX_BUFFER_SIZE 32767
/** @brief PDM error type. */
typedef enum
{
NRFX_PDM_NO_ERROR = 0, ///< No error.
NRFX_PDM_ERROR_OVERFLOW = 1 ///< Overflow error.
} nrfx_pdm_error_t;
/** @brief PDM event structure. */
typedef struct
{
bool buffer_requested; ///< Buffer request flag.
int16_t * buffer_released; ///< Pointer to the released buffer. Can be NULL.
nrfx_pdm_error_t error; ///< Error type.
} nrfx_pdm_evt_t;
/** @brief PDM interface driver configuration structure. */
typedef struct
{
nrf_pdm_mode_t mode; ///< Interface operation mode.
nrf_pdm_edge_t edge; ///< Sampling mode.
uint8_t pin_clk; ///< CLK pin.
uint8_t pin_din; ///< DIN pin.
nrf_pdm_freq_t clock_freq; ///< Clock frequency.
nrf_pdm_gain_t gain_l; ///< Left channel gain.
nrf_pdm_gain_t gain_r; ///< Right channel gain.
uint8_t interrupt_priority; ///< Interrupt priority.
} nrfx_pdm_config_t;
/**
* @brief Macro for setting @ref nrfx_pdm_config_t to default settings
* in the single-ended mode.
*
* @param _pin_clk CLK output pin.
* @param _pin_din DIN input pin.
*/
#define NRFX_PDM_DEFAULT_CONFIG(_pin_clk, _pin_din) \
{ \
.mode = (nrf_pdm_mode_t)NRFX_PDM_CONFIG_MODE, \
.edge = (nrf_pdm_edge_t)NRFX_PDM_CONFIG_EDGE, \
.pin_clk = _pin_clk, \
.pin_din = _pin_din, \
.clock_freq = (nrf_pdm_freq_t)NRFX_PDM_CONFIG_CLOCK_FREQ, \
.gain_l = NRF_PDM_GAIN_DEFAULT, \
.gain_r = NRF_PDM_GAIN_DEFAULT, \
.interrupt_priority = NRFX_PDM_CONFIG_IRQ_PRIORITY \
}
/**
* @brief Handler for the PDM interface ready events.
*
* This event handler is called on a buffer request, an error or when a buffer
* is full and ready to be processed.
*
* @param[in] p_evt Pointer to the PDM event structure.
*/
typedef void (*nrfx_pdm_event_handler_t)(nrfx_pdm_evt_t const * const p_evt);
/**
* @brief Function for initializing the PDM interface.
*
* @param[in] p_config Pointer to the structure with the initial configuration.
* @param[in] event_handler Event handler provided by the user. Cannot be NULL.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver is already initialized.
* @retval NRFX_ERROR_INVALID_PARAM Invalid configuration was specified.
*/
nrfx_err_t nrfx_pdm_init(nrfx_pdm_config_t const * p_config,
nrfx_pdm_event_handler_t event_handler);
/**
* @brief Function for uninitializing the PDM interface.
*
* This function stops PDM sampling, if it is in progress.
*/
void nrfx_pdm_uninit(void);
/**
* @brief Function for getting the address of a PDM interface task.
*
* @param[in] task Task.
*
* @return Task address.
*/
__STATIC_INLINE uint32_t nrfx_pdm_task_address_get(nrf_pdm_task_t task)
{
return nrf_pdm_task_address_get(task);
}
/**
* @brief Function for getting the state of the PDM interface.
*
* @retval true The PDM interface is enabled.
* @retval false The PDM interface is disabled.
*/
__STATIC_INLINE bool nrfx_pdm_enable_check(void)
{
return nrf_pdm_enable_check();
}
/**
* @brief Function for starting the PDM sampling.
*
* @retval NRFX_SUCCESS Sampling was started successfully or was already in progress.
* @retval NRFX_ERROR_BUSY Previous start/stop operation is in progress.
*/
nrfx_err_t nrfx_pdm_start(void);
/**
* @brief Function for stopping the PDM sampling.
*
* When this function is called, the PDM interface is stopped after finishing
* the current frame.
* The event handler function might be called once more after calling this function.
*
* @retval NRFX_SUCCESS Sampling was stopped successfully or was already stopped before.
* @retval NRFX_ERROR_BUSY Previous start/stop operation is in progress.
*/
nrfx_err_t nrfx_pdm_stop(void);
/**
* @brief Function for supplying the sample buffer.
*
* Call this function after every buffer request event.
*
* @param[in] buffer Pointer to the receive buffer. Cannot be NULL.
* @param[in] buffer_length Length of the receive buffer in 16-bit words.
*
* @retval NRFX_SUCCESS The buffer was applied successfully.
* @retval NRFX_ERROR_BUSY The buffer was already supplied or the peripheral is currently being stopped.
* @retval NRFX_ERROR_INVALID_STATE The driver was not initialized.
* @retval NRFX_ERROR_INVALID_PARAM Invalid parameters were provided.
*/
nrfx_err_t nrfx_pdm_buffer_set(int16_t * buffer, uint16_t buffer_length);
/** @} */
void nrfx_pdm_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_PDM_H__

View file

@ -1,371 +0,0 @@
/*
* Copyright (c) 2017 - 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_POWER_H__
#define NRFX_POWER_H__
#include <nrfx.h>
#include <hal/nrf_power.h>
#include <nrfx_power_clock.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_power POWER driver
* @{
* @ingroup nrf_power
* @brief POWER peripheral driver.
*/
/**
* @brief Power mode possible configurations
*/
typedef enum
{
NRFX_POWER_MODE_CONSTLAT, /**< Constant latency mode */
NRFX_POWER_MODE_LOWPWR /**< Low power mode */
}nrfx_power_mode_t;
#if NRF_POWER_HAS_SLEEPEVT || defined(__NRFX_DOXYGEN__)
/**
* @brief Events from power system
*/
typedef enum
{
NRFX_POWER_SLEEP_EVT_ENTER, /**< CPU entered WFI/WFE sleep
*
* Keep in mind that if this interrupt is enabled,
* it means that CPU was waken up just after WFI by this interrupt.
*/
NRFX_POWER_SLEEP_EVT_EXIT /**< CPU exited WFI/WFE sleep */
}nrfx_power_sleep_evt_t;
#endif /* NRF_POWER_HAS_SLEEPEVT */
#if NRF_POWER_HAS_USBREG || defined(__NRFX_DOXYGEN__)
/**
* @brief Events from USB power system
*/
typedef enum
{
NRFX_POWER_USB_EVT_DETECTED, /**< USB power detected on the connector (plugged in). */
NRFX_POWER_USB_EVT_REMOVED, /**< USB power removed from the connector. */
NRFX_POWER_USB_EVT_READY /**< USB power regulator ready. */
}nrfx_power_usb_evt_t;
/**
* @brief USB power state
*
* The single enumerator that holds all data about current state of USB
* related POWER.
*
* Organized this way that higher power state has higher numeric value
*/
typedef enum
{
NRFX_POWER_USB_STATE_DISCONNECTED, /**< No power on USB lines detected. */
NRFX_POWER_USB_STATE_CONNECTED, /**< The USB power is detected, but USB power regulator is not ready. */
NRFX_POWER_USB_STATE_READY /**< From the power viewpoint, USB is ready for working. */
}nrfx_power_usb_state_t;
#endif /* NRF_POWER_HAS_USBREG */
/**
* @name Callback types
*
* Defined types of callback functions.
* @{
*/
/**
* @brief Event handler for power failure warning.
*/
typedef void (*nrfx_power_pofwarn_event_handler_t)(void);
#if NRF_POWER_HAS_SLEEPEVT || defined(__NRFX_DOXYGEN__)
/**
* @brief Event handler for the sleep events.
*
* @param event Event type
*/
typedef void (*nrfx_power_sleep_event_handler_t)(nrfx_power_sleep_evt_t event);
#endif
#if NRF_POWER_HAS_USBREG || defined(__NRFX_DOXYGEN__)
/**
* @brief Event handler for the USB-related power events.
*
* @param event Event type
*/
typedef void (*nrfx_power_usb_event_handler_t)(nrfx_power_usb_evt_t event);
#endif
/** @} */
/**
* @brief General power configuration
*
* Parameters required to initialize power driver.
*/
typedef struct
{
/**
* @brief Enable main DCDC regulator.
*
* This bit only informs the driver that elements for DCDC regulator
* are installed and the regulator can be used.
* The regulator will be enabled or disabled automatically
* by the hardware, basing on current power requirement.
*/
bool dcdcen:1;
#if NRF_POWER_HAS_VDDH || defined(__NRFX_DOXYGEN__)
/**
* @brief Enable HV DCDC regulator.
*
* This bit only informs the driver that elements for DCDC regulator
* are installed and the regulator can be used.
* The regulator will be enabled or disabled automatically
* by the hardware, basing on current power requirement.
*/
bool dcdcenhv: 1;
#endif
}nrfx_power_config_t;
/**
* @brief The configuration for power failure comparator.
*
* Configuration used to enable and configure the power failure comparator.
*/
typedef struct
{
nrfx_power_pofwarn_event_handler_t handler; //!< Event handler.
#if NRF_POWER_HAS_POFCON || defined(__NRFX_DOXYGEN__)
nrf_power_pof_thr_t thr; //!< Threshold for power failure detection
#endif
#if NRF_POWER_HAS_VDDH || defined(__NRFX_DOXYGEN__)
nrf_power_pof_thrvddh_t thrvddh; //!< Threshold for power failure detection on the VDDH pin.
#endif
}nrfx_power_pofwarn_config_t;
#if NRF_POWER_HAS_SLEEPEVT || defined(__NRFX_DOXYGEN__)
/**
* @brief The configuration of sleep event processing.
*
* Configuration used to enable and configure sleep event handling.
*/
typedef struct
{
nrfx_power_sleep_event_handler_t handler; //!< Event handler.
bool en_enter:1; //!< Enable event on sleep entering.
bool en_exit :1; //!< Enable event on sleep exiting.
}nrfx_power_sleepevt_config_t;
#endif
#if NRF_POWER_HAS_USBREG || defined(__NRFX_DOXYGEN__)
/**
* @brief The configuration of the USB-related power events.
*
* Configuration used to enable and configure USB power event handling.
*/
typedef struct
{
nrfx_power_usb_event_handler_t handler; //!< Event processing.
}nrfx_power_usbevt_config_t;
#endif /* NRF_POWER_HAS_USBREG */
/**
* @brief Function for getting the handler of the power failure comparator.
* @return Handler of the power failure comparator.
*/
nrfx_power_pofwarn_event_handler_t nrfx_power_pof_handler_get(void);
#if NRF_POWER_HAS_USBREG || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for getting the handler of the USB power.
* @return Handler of the USB power.
*/
nrfx_power_usb_event_handler_t nrfx_power_usb_handler_get(void);
#endif
/**
* @brief Function for initializing the power module driver.
*
* Enabled power module driver processes all the interrupts from the power system.
*
* @param[in] p_config Pointer to the structure with the initial configuration.
*
* @retval NRFX_SUCCESS Successfully initialized.
* @retval NRFX_ERROR_ALREADY_INITIALIZED Module was already initialized.
*/
nrfx_err_t nrfx_power_init(nrfx_power_config_t const * p_config);
/**
* @brief Function for unintializing the power module driver.
*
* Disables all the interrupt handling in the module.
*
* @sa nrfx_power_init
*/
void nrfx_power_uninit(void);
#if NRF_POWER_HAS_POFCON || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for initializing the power failure comparator.
*
* Configures the power failure comparator. This function does not set it up and enable it.
* These steps can be done with functions @ref nrfx_power_pof_enable and @ref nrfx_power_pof_disable
* or with the SoftDevice API (when in use).
*
* @param[in] p_config Configuration with values and event handler.
* If event handler is set to NULL, the interrupt will be disabled.
*/
void nrfx_power_pof_init(nrfx_power_pofwarn_config_t const * p_config);
/**
* @brief Function for enabling the power failure comparator.
* Sets and enables the interrupt of the power failure comparator. This function cannot be in use
* when SoftDevice is enabled. If the event handler set in the init function is set to NULL, the interrupt
* will be disabled.
*
* @param[in] p_config Configuration with values and event handler.
*/
void nrfx_power_pof_enable(nrfx_power_pofwarn_config_t const * p_config);
/**
* @brief Function for disabling the power failure comparator.
*
* Disables the power failure comparator interrupt.
*/
void nrfx_power_pof_disable(void);
/**
* @brief Function for clearing the power failure comparator settings.
*
* Clears the settings of the power failure comparator.
*/
void nrfx_power_pof_uninit(void);
#endif // NRF_POWER_HAS_POFCON || defined(__NRFX_DOXYGEN__)
#if NRF_POWER_HAS_SLEEPEVT || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for initializing the processing of the sleep events.
*
* Configures and sets up the sleep event processing.
*
* @param[in] p_config Configuration with values and event handler.
*
* @sa nrfx_power_sleepevt_uninit
*
*/
void nrfx_power_sleepevt_init(nrfx_power_sleepevt_config_t const * p_config);
/**
* @brief Function for enabling the processing of the sleep events.
*
* @param[in] p_config Configuration with values and event handler.
*/
void nrfx_power_sleepevt_enable(nrfx_power_sleepevt_config_t const * p_config);
/** @brief Function for disabling the processing of the sleep events. */
void nrfx_power_sleepevt_disable(void);
/**
* @brief Function for uninitializing the processing of the sleep events.
*
* @sa nrfx_power_sleepevt_init
*/
void nrfx_power_sleepevt_uninit(void);
#endif /* NRF_POWER_HAS_SLEEPEVT */
#if NRF_POWER_HAS_USBREG || defined(__NRFX_DOXYGEN__)
/**
* @brief Function for initializing the processing of USB power event.
*
* Configures and sets up the USB power event processing.
*
* @param[in] p_config Configuration with values and event handler.
*
* @sa nrfx_power_usbevt_uninit
*/
void nrfx_power_usbevt_init(nrfx_power_usbevt_config_t const * p_config);
/** @brief Function for enabling the processing of USB power event. */
void nrfx_power_usbevt_enable(void);
/** @brief Function for disabling the processing of USB power event. */
void nrfx_power_usbevt_disable(void);
/**
* @brief Function for uninitalizing the processing of USB power event.
*
* @sa nrfx_power_usbevt_init
*/
void nrfx_power_usbevt_uninit(void);
/**
* @brief Function for getting the status of USB power.
*
* @return Current USB power status.
*/
__STATIC_INLINE nrfx_power_usb_state_t nrfx_power_usbstatus_get(void);
#endif /* NRF_POWER_HAS_USBREG */
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
#if NRF_POWER_HAS_USBREG
__STATIC_INLINE nrfx_power_usb_state_t nrfx_power_usbstatus_get(void)
{
uint32_t status = nrf_power_usbregstatus_get();
if(0 == (status & NRF_POWER_USBREGSTATUS_VBUSDETECT_MASK))
{
return NRFX_POWER_USB_STATE_DISCONNECTED;
}
if(0 == (status & NRF_POWER_USBREGSTATUS_OUTPUTRDY_MASK))
{
return NRFX_POWER_USB_STATE_CONNECTED;
}
return NRFX_POWER_USB_STATE_READY;
}
#endif /* NRF_POWER_HAS_USBREG */
#endif /* SUPPRESS_INLINE_IMPLEMENTATION */
/** @} */
void nrfx_power_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif /* NRFX_POWER_H__ */

View file

@ -1,83 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_POWER_CLOCK_H__
#define NRFX_POWER_CLOCK_H__
#include <nrfx.h>
#ifdef __cplusplus
extern "C" {
#endif
__STATIC_INLINE void nrfx_power_clock_irq_init(void);
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE void nrfx_power_clock_irq_init(void)
{
uint8_t priority;
#if NRFX_CHECK(NRFX_POWER_ENABLED) && NRFX_CHECK(NRFX_CLOCK_ENABLED)
#if NRFX_POWER_CONFIG_IRQ_PRIORITY != NRFX_CLOCK_CONFIG_IRQ_PRIORITY
#error "IRQ priorities for POWER and CLOCK must be the same. Check <nrfx_config.h>."
#endif
priority = NRFX_POWER_CONFIG_IRQ_PRIORITY;
#elif NRFX_CHECK(NRFX_POWER_ENABLED)
priority = NRFX_POWER_CONFIG_IRQ_PRIORITY;
#elif NRFX_CHECK(NRFX_CLOCK_ENABLED)
priority = NRFX_CLOCK_CONFIG_IRQ_PRIORITY;
#else
#error "This code is not supposed to be compiled when neither POWER nor CLOCK is enabled."
#endif
if (!NRFX_IRQ_IS_ENABLED(nrfx_get_irq_number(NRF_CLOCK)))
{
NRFX_IRQ_PRIORITY_SET(nrfx_get_irq_number(NRF_CLOCK), priority);
NRFX_IRQ_ENABLE(nrfx_get_irq_number(NRF_CLOCK));
}
}
#endif // SUPPRESS_INLINE_IMPLEMENTATION
#if NRFX_CHECK(NRFX_POWER_ENABLED) && NRFX_CHECK(NRFX_CLOCK_ENABLED)
void nrfx_power_clock_irq_handler(void);
#elif NRFX_CHECK(NRFX_POWER_ENABLED)
#define nrfx_power_irq_handler nrfx_power_clock_irq_handler
#elif NRFX_CHECK(NRFX_CLOCK_ENABLED)
#define nrfx_clock_irq_handler nrfx_power_clock_irq_handler
#endif
#ifdef __cplusplus
}
#endif
#endif // NRFX_POWER_CLOCK_H__

View file

@ -1,322 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_PPI_H__
#define NRFX_PPI_H__
#include <nrfx.h>
#include <hal/nrf_ppi.h>
/**
* @defgroup nrfx_ppi PPI allocator
* @{
* @ingroup nrf_ppi
* @brief Programmable Peripheral Interconnect (PPI) allocator.
*/
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (NRFX_PPI_CHANNELS_USED) || defined(__NRFX_DOXYGEN__)
/** @brief Bitfield representing PPI channels used by external modules. */
#define NRFX_PPI_CHANNELS_USED 0
#endif
#if !defined(NRFX_PPI_GROUPS_USED) || defined(__NRFX_DOXYGEN__)
/** @brief Bitfield representing PPI groups used by external modules. */
#define NRFX_PPI_GROUPS_USED 0
#endif
#if (PPI_CH_NUM > 16) || defined(__NRFX_DOXYGEN__)
/** @brief Bitfield representing all PPI channels available to the application. */
#define NRFX_PPI_ALL_APP_CHANNELS_MASK ((uint32_t)0xFFFFFFFFuL & ~(NRFX_PPI_CHANNELS_USED))
/** @brief Bitfield representing programmable PPI channels available to the application. */
#define NRFX_PPI_PROG_APP_CHANNELS_MASK ((uint32_t)0x000FFFFFuL & ~(NRFX_PPI_CHANNELS_USED))
#else
#define NRFX_PPI_ALL_APP_CHANNELS_MASK ((uint32_t)0xFFF0FFFFuL & ~(NRFX_PPI_CHANNELS_USED))
#define NRFX_PPI_PROG_APP_CHANNELS_MASK ((uint32_t)0x0000FFFFuL & ~(NRFX_PPI_CHANNELS_USED))
#endif
/** @brief Bitfield representing all PPI groups available to the application. */
#define NRFX_PPI_ALL_APP_GROUPS_MASK (((1uL << PPI_GROUP_NUM) - 1) & ~(NRFX_PPI_GROUPS_USED))
/**
* @brief Function for uninitializing the PPI module.
*
* This function disables all channels and clears the channel groups.
*/
void nrfx_ppi_free_all(void);
/**
* @brief Function for allocating a PPI channel.
* @details This function allocates the first unused PPI channel.
*
* @param[out] p_channel Pointer to the PPI channel that has been allocated.
*
* @retval NRFX_SUCCESS The channel was successfully allocated.
* @retval NRFX_ERROR_NO_MEM There is no available channel to be used.
*/
nrfx_err_t nrfx_ppi_channel_alloc(nrf_ppi_channel_t * p_channel);
/**
* @brief Function for freeing a PPI channel.
* @details This function also disables the chosen channel.
*
* @param[in] channel PPI channel to be freed.
*
* @retval NRFX_SUCCESS The channel was successfully freed.
* @retval NRFX_ERROR_INVALID_PARAM The channel is not user-configurable.
*/
nrfx_err_t nrfx_ppi_channel_free(nrf_ppi_channel_t channel);
/**
* @brief Function for assigning task and event endpoints to the PPI channel.
*
* @param[in] channel PPI channel to be assigned endpoints.
* @param[in] eep Event endpoint address.
* @param[in] tep Task endpoint address.
*
* @retval NRFX_SUCCESS The channel was successfully assigned.
* @retval NRFX_ERROR_INVALID_STATE The channel is not allocated for the user.
* @retval NRFX_ERROR_INVALID_PARAM The channel is not user-configurable.
*/
nrfx_err_t nrfx_ppi_channel_assign(nrf_ppi_channel_t channel, uint32_t eep, uint32_t tep);
/**
* @brief Function for assigning fork endpoint to the PPI channel or clearing it.
*
* @param[in] channel PPI channel to be assigned endpoints.
* @param[in] fork_tep Fork task endpoint address or 0 to clear.
*
* @retval NRFX_SUCCESS The channel was successfully assigned.
* @retval NRFX_ERROR_INVALID_STATE The channel is not allocated for the user.
* @retval NRFX_ERROR_NOT_SUPPORTED Function is not supported.
*/
nrfx_err_t nrfx_ppi_channel_fork_assign(nrf_ppi_channel_t channel, uint32_t fork_tep);
/**
* @brief Function for enabling a PPI channel.
*
* @param[in] channel PPI channel to be enabled.
*
* @retval NRFX_SUCCESS The channel was successfully enabled.
* @retval NRFX_ERROR_INVALID_STATE The user-configurable channel is not allocated.
* @retval NRFX_ERROR_INVALID_PARAM The channel cannot be enabled by the user.
*/
nrfx_err_t nrfx_ppi_channel_enable(nrf_ppi_channel_t channel);
/**
* @brief Function for disabling a PPI channel.
*
* @param[in] channel PPI channel to be disabled.
*
* @retval NRFX_SUCCESS The channel was successfully disabled.
* @retval NRFX_ERROR_INVALID_STATE The user-configurable channel is not allocated.
* @retval NRFX_ERROR_INVALID_PARAM The channel cannot be disabled by the user.
*/
nrfx_err_t nrfx_ppi_channel_disable(nrf_ppi_channel_t channel);
/**
* @brief Function for allocating a PPI channel group.
* @details This function allocates the first unused PPI group.
*
* @param[out] p_group Pointer to the PPI channel group that has been allocated.
*
* @retval NRFX_SUCCESS The channel group was successfully allocated.
* @retval NRFX_ERROR_NO_MEM There is no available channel group to be used.
*/
nrfx_err_t nrfx_ppi_group_alloc(nrf_ppi_channel_group_t * p_group);
/**
* @brief Function for freeing a PPI channel group.
* @details This function also disables the chosen group.
*
* @param[in] group PPI channel group to be freed.
*
* @retval NRFX_SUCCESS The channel group was successfully freed.
* @retval NRFX_ERROR_INVALID_PARAM The channel group is not user-configurable.
*/
nrfx_err_t nrfx_ppi_group_free(nrf_ppi_channel_group_t group);
/**
* @brief Compute a channel mask for NRF_PPI registers.
*
* @param[in] channel Channel number to transform to a mask.
*
* @return Channel mask.
*/
__STATIC_INLINE uint32_t nrfx_ppi_channel_to_mask(nrf_ppi_channel_t channel)
{
return (1uL << (uint32_t) channel);
}
/**
* @brief Function for including multiple PPI channels in a channel group.
*
* @param[in] channel_mask PPI channels to be added.
* @param[in] group Channel group in which to include the channels.
*
* @retval NRFX_SUCCESS The channels was successfully included.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group or channels are not an
* application channels.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
nrfx_err_t nrfx_ppi_channels_include_in_group(uint32_t channel_mask,
nrf_ppi_channel_group_t group);
/**
* @brief Function for including a PPI channel in a channel group.
*
* @param[in] channel PPI channel to be added.
* @param[in] group Channel group in which to include the channel.
*
* @retval NRFX_SUCCESS The channel was successfully included.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group or channel is not an
* application channel.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
__STATIC_INLINE nrfx_err_t nrfx_ppi_channel_include_in_group(nrf_ppi_channel_t channel,
nrf_ppi_channel_group_t group)
{
return nrfx_ppi_channels_include_in_group(nrfx_ppi_channel_to_mask(channel), group);
}
/**
* @brief Function for removing multiple PPI channels from a channel group.
*
* @param[in] channel_mask PPI channels to be removed.
* @param[in] group Channel group from which to remove the channels.
*
* @retval NRFX_SUCCESS The channel was successfully removed.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group or channels are not an
* application channels.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
nrfx_err_t nrfx_ppi_channels_remove_from_group(uint32_t channel_mask,
nrf_ppi_channel_group_t group);
/**
* @brief Function for removing a single PPI channel from a channel group.
*
* @param[in] channel PPI channel to be removed.
* @param[in] group Channel group from which to remove the channel.
*
* @retval NRFX_SUCCESS The channel was successfully removed.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group or channel is not an
* application channel.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
__STATIC_INLINE nrfx_err_t nrfx_ppi_channel_remove_from_group(nrf_ppi_channel_t channel,
nrf_ppi_channel_group_t group)
{
return nrfx_ppi_channels_remove_from_group(nrfx_ppi_channel_to_mask(channel), group);
}
/**
* @brief Function for clearing a PPI channel group.
*
* @param[in] group Channel group to be cleared.
*
* @retval NRFX_SUCCESS The group was successfully cleared.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
__STATIC_INLINE nrfx_err_t nrfx_ppi_group_clear(nrf_ppi_channel_group_t group)
{
return nrfx_ppi_channels_remove_from_group(NRFX_PPI_ALL_APP_CHANNELS_MASK, group);
}
/**
* @brief Function for enabling a PPI channel group.
*
* @param[in] group Channel group to be enabled.
*
* @retval NRFX_SUCCESS The group was successfully enabled.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
nrfx_err_t nrfx_ppi_group_enable(nrf_ppi_channel_group_t group);
/**
* @brief Function for disabling a PPI channel group.
*
* @param[in] group Channel group to be disabled.
*
* @retval NRFX_SUCCESS The group was successfully disabled.
* @retval NRFX_ERROR_INVALID_PARAM Group is not an application group.
* @retval NRFX_ERROR_INVALID_STATE Group is not an allocated group.
*/
nrfx_err_t nrfx_ppi_group_disable(nrf_ppi_channel_group_t group);
/**
* @brief Function for getting the address of a PPI task.
*
* @param[in] task Task.
*
* @return Task address.
*/
__STATIC_INLINE uint32_t nrfx_ppi_task_addr_get(nrf_ppi_task_t task)
{
return (uint32_t) nrf_ppi_task_address_get(task);
}
/**
* @brief Function for getting the address of the enable task of a PPI group.
*
* @param[in] group PPI channel group
*
* @return Task address.
*/
__STATIC_INLINE uint32_t nrfx_ppi_task_addr_group_enable_get(nrf_ppi_channel_group_t group)
{
return (uint32_t) nrf_ppi_task_group_enable_address_get(group);
}
/**
* @brief Function for getting the address of the enable task of a PPI group.
*
* @param[in] group PPI channel group
*
* @return Task address.
*/
__STATIC_INLINE uint32_t nrfx_ppi_task_addr_group_disable_get(nrf_ppi_channel_group_t group)
{
return (uint32_t) nrf_ppi_task_group_disable_address_get(group);
}
/** @} */
#ifdef __cplusplus
}
#endif
#endif // NRFX_PPI_H__

View file

@ -1,467 +0,0 @@
/*
* 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 must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef NRFX_PWM_H__
#define NRFX_PWM_H__
#include <nrfx.h>
#include <hal/nrf_pwm.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* @defgroup nrfx_pwm PWM driver
* @{
* @ingroup nrf_pwm
* @brief Pulse Width Modulation (PWM) peripheral driver.
*/
/** @brief PWM driver instance data structure. */
typedef struct
{
NRF_PWM_Type * p_registers; ///< Pointer to the structure with PWM peripheral instance registers.
uint8_t drv_inst_idx; ///< Index of the driver instance. For internal use only.
} nrfx_pwm_t;
/** @brief Macro for creating a PWM driver instance. */
#define NRFX_PWM_INSTANCE(id) \
{ \
.p_registers = NRFX_CONCAT_2(NRF_PWM, id), \
.drv_inst_idx = NRFX_CONCAT_3(NRFX_PWM, id, _INST_IDX), \
}
#ifndef __NRFX_DOXYGEN__
enum {
#if NRFX_CHECK(NRFX_PWM0_ENABLED)
NRFX_PWM0_INST_IDX,
#endif
#if NRFX_CHECK(NRFX_PWM1_ENABLED)
NRFX_PWM1_INST_IDX,
#endif
#if NRFX_CHECK(NRFX_PWM2_ENABLED)
NRFX_PWM2_INST_IDX,
#endif
#if NRFX_CHECK(NRFX_PWM3_ENABLED)
NRFX_PWM3_INST_IDX,
#endif
NRFX_PWM_ENABLED_COUNT
};
#endif
/**
* @brief This value can be provided instead of a pin number for any channel
* to specify that its output is not used and therefore does not need
* to be connected to a pin.
*/
#define NRFX_PWM_PIN_NOT_USED 0xFF
/** @brief This value can be added to a pin number to invert its polarity (set idle state = 1). */
#define NRFX_PWM_PIN_INVERTED 0x80
/** @brief PWM driver configuration structure. */
typedef struct
{
uint8_t output_pins[NRF_PWM_CHANNEL_COUNT]; ///< Pin numbers for individual output channels (optional).
/**< Use @ref NRFX_PWM_PIN_NOT_USED
* if a given output channel is not needed. */
uint8_t irq_priority; ///< Interrupt priority.
nrf_pwm_clk_t base_clock; ///< Base clock frequency.
nrf_pwm_mode_t count_mode; ///< Operating mode of the pulse generator counter.
uint16_t top_value; ///< Value up to which the pulse generator counter counts.
nrf_pwm_dec_load_t load_mode; ///< Mode of loading sequence data from RAM.
nrf_pwm_dec_step_t step_mode; ///< Mode of advancing the active sequence.
} nrfx_pwm_config_t;
/** @brief PWM driver default configuration. */
#define NRFX_PWM_DEFAULT_CONFIG \
{ \
.output_pins = { NRFX_PWM_DEFAULT_CONFIG_OUT0_PIN, \
NRFX_PWM_DEFAULT_CONFIG_OUT1_PIN, \
NRFX_PWM_DEFAULT_CONFIG_OUT2_PIN, \
NRFX_PWM_DEFAULT_CONFIG_OUT3_PIN }, \
.irq_priority = NRFX_PWM_DEFAULT_CONFIG_IRQ_PRIORITY, \
.base_clock = (nrf_pwm_clk_t)NRFX_PWM_DEFAULT_CONFIG_BASE_CLOCK, \
.count_mode = (nrf_pwm_mode_t)NRFX_PWM_DEFAULT_CONFIG_COUNT_MODE, \
.top_value = NRFX_PWM_DEFAULT_CONFIG_TOP_VALUE, \
.load_mode = (nrf_pwm_dec_load_t)NRFX_PWM_DEFAULT_CONFIG_LOAD_MODE, \
.step_mode = (nrf_pwm_dec_step_t)NRFX_PWM_DEFAULT_CONFIG_STEP_MODE, \
}
/** @brief PWM flags that provide additional playback options. */
typedef enum
{
NRFX_PWM_FLAG_STOP = 0x01, /**< When the requested playback is finished,
the peripheral will be stopped.
@note The STOP task is triggered when
the last value of the final sequence is
loaded from RAM, and the peripheral stops
at the end of the current PWM period.
For sequences with configured repeating
of duty cycle values, this might result in
less than the requested number of repeats
of the last value. */
NRFX_PWM_FLAG_LOOP = 0x02, /**< When the requested playback is finished,
it will be started from the beginning.
This flag is ignored if used together
with @ref NRFX_PWM_FLAG_STOP.
@note The playback restart is done via a
shortcut configured in the PWM peripheral.
This shortcut triggers the proper starting
task when the final value of previous
playback is read from RAM and applied to
the pulse generator counter.
When this mechanism is used together with
the @ref NRF_PWM_STEP_TRIGGERED mode,
the playback restart will occur right
after switching to the final value (this
final value will be played only once). */
NRFX_PWM_FLAG_SIGNAL_END_SEQ0 = 0x04, /**< The event handler is to be
called when the last value
from sequence 0 is loaded. */
NRFX_PWM_FLAG_SIGNAL_END_SEQ1 = 0x08, /**< The event handler is to be
called when the last value
from sequence 1 is loaded. */
NRFX_PWM_FLAG_NO_EVT_FINISHED = 0x10, /**< The playback finished event
(enabled by default) is to be
suppressed. */
NRFX_PWM_FLAG_START_VIA_TASK = 0x80, /**< The playback must not be
started directly by the called
function. Instead, the function
must only prepare it and
return the address of the task
to be triggered to start the
playback. */
} nrfx_pwm_flag_t;
/** @brief PWM driver event type. */
typedef enum
{
NRFX_PWM_EVT_FINISHED, ///< Sequence playback finished.
NRFX_PWM_EVT_END_SEQ0, /**< End of sequence 0 reached. Its data can be
safely modified now. */
NRFX_PWM_EVT_END_SEQ1, /**< End of sequence 1 reached. Its data can be
safely modified now. */
NRFX_PWM_EVT_STOPPED, ///< The PWM peripheral has been stopped.
} nrfx_pwm_evt_type_t;
/** @brief PWM driver event handler type. */
typedef void (* nrfx_pwm_handler_t)(nrfx_pwm_evt_type_t event_type);
/**
* @brief Function for initializing the PWM driver.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] p_config Pointer to the structure with the initial configuration.
* @param[in] handler Event handler provided by the user. If NULL is passed
* instead, event notifications are not done and PWM
* interrupts are disabled.
*
* @retval NRFX_SUCCESS Initialization was successful.
* @retval NRFX_ERROR_INVALID_STATE The driver was already initialized.
*/
nrfx_err_t nrfx_pwm_init(nrfx_pwm_t const * const p_instance,
nrfx_pwm_config_t const * p_config,
nrfx_pwm_handler_t handler);
/**
* @brief Function for uninitializing the PWM driver.
*
* If any sequence playback is in progress, it is stopped immediately.
*
* @param[in] p_instance Pointer to the driver instance structure.
*/
void nrfx_pwm_uninit(nrfx_pwm_t const * const p_instance);
/**
* @brief Function for starting a single sequence playback.
*
* To take advantage of the looping mechanism in the PWM peripheral, both
* sequences must be used (single sequence can be played back only once by
* the peripheral). Therefore, the provided sequence is internally set and
* played back as both sequence 0 and sequence 1. Consequently, if the end of
* sequence notifications are required, events for both sequences must be
* used (that is, both the @ref NRFX_PWM_FLAG_SIGNAL_END_SEQ0 flag
* and the @ref NRFX_PWM_FLAG_SIGNAL_END_SEQ1 flag must be specified, and
* the @ref NRFX_PWM_EVT_END_SEQ0 event and the @ref NRFX_PWM_EVT_END_SEQ1
* event must be handled in the same way).
*
* Use the @ref NRFX_PWM_FLAG_START_VIA_TASK flag if you want the playback
* to be only prepared by this function, and you want to start it later by
* triggering a task (for example, by using PPI). The function will then return
* the address of the task to be triggered.
*
* @note The array containing the duty cycle values for the specified sequence
* must be in RAM and cannot be allocated on the stack.
* For detailed information, see @ref nrf_pwm_sequence_t.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] p_sequence Sequence to be played back.
* @param[in] playback_count Number of playbacks to be performed (must not be 0).
* @param[in] flags Additional options. Pass any combination of
* @ref nrfx_pwm_flag_t "playback flags", or 0
* for default settings.
*
* @return Address of the task to be triggered to start the playback if the @ref
* NRFX_PWM_FLAG_START_VIA_TASK flag was used, 0 otherwise.
*/
uint32_t nrfx_pwm_simple_playback(nrfx_pwm_t const * const p_instance,
nrf_pwm_sequence_t const * p_sequence,
uint16_t playback_count,
uint32_t flags);
/**
* @brief Function for starting a two-sequence playback.
*
* Use the @ref NRFX_PWM_FLAG_START_VIA_TASK flag if you want the playback
* to be only prepared by this function, and you want to start it later by
* triggering a task (using PPI for instance). The function will then return
* the address of the task to be triggered.
*
* @note The array containing the duty cycle values for the specified sequence
* must be in RAM and cannot be allocated on the stack.
* For detailed information, see @ref nrf_pwm_sequence_t.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] p_sequence_0 First sequence to be played back.
* @param[in] p_sequence_1 Second sequence to be played back.
* @param[in] playback_count Number of playbacks to be performed (must not be 0).
* @param[in] flags Additional options. Pass any combination of
* @ref nrfx_pwm_flag_t "playback flags", or 0
* for default settings.
*
* @return Address of the task to be triggered to start the playback if the @ref
* NRFX_PWM_FLAG_START_VIA_TASK flag was used, 0 otherwise.
*/
uint32_t nrfx_pwm_complex_playback(nrfx_pwm_t const * const p_instance,
nrf_pwm_sequence_t const * p_sequence_0,
nrf_pwm_sequence_t const * p_sequence_1,
uint16_t playback_count,
uint32_t flags);
/**
* @brief Function for advancing the active sequence.
*
* This function only applies to @ref NRF_PWM_STEP_TRIGGERED mode.
*
* @param[in] p_instance Pointer to the driver instance structure.
*/
__STATIC_INLINE void nrfx_pwm_step(nrfx_pwm_t const * const p_instance);
/**
* @brief Function for stopping the sequence playback.
*
* The playback is stopped at the end of the current PWM period.
* This means that if the active sequence is configured to repeat each duty
* cycle value for a certain number of PWM periods, the last played value
* might appear on the output less times than requested.
*
* @note This function can be instructed to wait until the playback is stopped
* (by setting @p wait_until_stopped to true). Depending on
* the length of the PMW period, this might take a significant amount of
* time. Alternatively, the @ref nrfx_pwm_is_stopped function can be
* used to poll the status, or the @ref NRFX_PWM_EVT_STOPPED event can
* be used to get the notification when the playback is stopped, provided
* the event handler is defined.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] wait_until_stopped If true, the function will not return until
* the playback is stopped.
*
* @retval true The PWM peripheral is stopped.
* @retval false The PWM peripheral is not stopped.
*/
bool nrfx_pwm_stop(nrfx_pwm_t const * const p_instance, bool wait_until_stopped);
/**
* @brief Function for checking the status of the PWM peripheral.
*
* @param[in] p_instance Pointer to the driver instance structure.
*
* @retval true The PWM peripheral is stopped.
* @retval false The PWM peripheral is not stopped.
*/
bool nrfx_pwm_is_stopped(nrfx_pwm_t const * const p_instance);
/**
* @brief Function for updating the sequence data during playback.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] seq_id Identifier of the sequence (0 or 1).
* @param[in] p_sequence Pointer to the new sequence definition.
*/
__STATIC_INLINE void nrfx_pwm_sequence_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
nrf_pwm_sequence_t const * p_sequence);
/**
* @brief Function for updating the pointer to the duty cycle values
* in the specified sequence during playback.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] seq_id Identifier of the sequence (0 or 1).
* @param[in] values New pointer to the duty cycle values.
*/
__STATIC_INLINE void nrfx_pwm_sequence_values_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
nrf_pwm_values_t values);
/**
* @brief Function for updating the number of duty cycle values
* in the specified sequence during playback.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] seq_id Identifier of the sequence (0 or 1).
* @param[in] length New number of the duty cycle values.
*/
__STATIC_INLINE void nrfx_pwm_sequence_length_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
uint16_t length);
/**
* @brief Function for updating the number of repeats for duty cycle values
* in the specified sequence during playback.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] seq_id Identifier of the sequence (0 or 1).
* @param[in] repeats New number of repeats.
*/
__STATIC_INLINE void nrfx_pwm_sequence_repeats_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
uint32_t repeats);
/**
* @brief Function for updating the additional delay after the specified
* sequence during playback.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] seq_id Identifier of the sequence (0 or 1).
* @param[in] end_delay New end delay value (in PWM periods).
*/
__STATIC_INLINE void nrfx_pwm_sequence_end_delay_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
uint32_t end_delay);
/**
* @brief Function for returning the address of a specified PWM task that can
* be used in PPI module.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] task Requested task.
*
* @return Task address.
*/
__STATIC_INLINE uint32_t nrfx_pwm_task_address_get(nrfx_pwm_t const * const p_instance,
nrf_pwm_task_t task);
/**
* @brief Function for returning the address of a specified PWM event that can
* be used in PPI module.
*
* @param[in] p_instance Pointer to the driver instance structure.
* @param[in] event Requested event.
*
* @return Event address.
*/
__STATIC_INLINE uint32_t nrfx_pwm_event_address_get(nrfx_pwm_t const * const p_instance,
nrf_pwm_event_t event);
#ifndef SUPPRESS_INLINE_IMPLEMENTATION
__STATIC_INLINE void nrfx_pwm_step(nrfx_pwm_t const * const p_instance)
{
nrf_pwm_task_trigger(p_instance->p_registers, NRF_PWM_TASK_NEXTSTEP);
}
__STATIC_INLINE void nrfx_pwm_sequence_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
nrf_pwm_sequence_t const * p_sequence)
{
nrf_pwm_sequence_set(p_instance->p_registers, seq_id, p_sequence);
}
__STATIC_INLINE void nrfx_pwm_sequence_values_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
nrf_pwm_values_t values)
{
nrf_pwm_seq_ptr_set(p_instance->p_registers, seq_id, values.p_raw);
}
__STATIC_INLINE void nrfx_pwm_sequence_length_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
uint16_t length)
{
nrf_pwm_seq_cnt_set(p_instance->p_registers, seq_id, length);
}
__STATIC_INLINE void nrfx_pwm_sequence_repeats_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
uint32_t repeats)
{
nrf_pwm_seq_refresh_set(p_instance->p_registers, seq_id, repeats);
}
__STATIC_INLINE void nrfx_pwm_sequence_end_delay_update(nrfx_pwm_t const * const p_instance,
uint8_t seq_id,
uint32_t end_delay)
{
nrf_pwm_seq_end_delay_set(p_instance->p_registers, seq_id, end_delay);
}
__STATIC_INLINE uint32_t nrfx_pwm_task_address_get(nrfx_pwm_t const * const p_instance,
nrf_pwm_task_t task)
{
return nrf_pwm_task_address_get(p_instance->p_registers, task);
}
__STATIC_INLINE uint32_t nrfx_pwm_event_address_get(nrfx_pwm_t const * const p_instance,
nrf_pwm_event_t event)
{
return nrf_pwm_event_address_get(p_instance->p_registers, event);
}
#endif // SUPPRESS_INLINE_IMPLEMENTATION
/** @} */
void nrfx_pwm_0_irq_handler(void);
void nrfx_pwm_1_irq_handler(void);
void nrfx_pwm_2_irq_handler(void);
void nrfx_pwm_3_irq_handler(void);
#ifdef __cplusplus
}
#endif
#endif // NRFX_PWM_H__

Some files were not shown because too many files have changed in this diff Show more