cc26xx: implement poll mode, hardware timestamps, and other minor changes in the IEEE radio driver

This commit is contained in:
Atis Elsts 2016-04-25 17:58:24 +03:00
parent 3ff8aa8ad8
commit ac6f8008fd
4 changed files with 328 additions and 72 deletions

View file

@ -51,6 +51,7 @@
#include "sys/energest.h"
#include "sys/clock.h"
#include "sys/rtimer.h"
#include "sys/ctimer.h"
#include "sys/cc.h"
#include "lpm.h"
#include "ti-lib.h"
@ -102,6 +103,9 @@
#define IEEE_MODE_RSSI_THRESHOLD 0xA6
#endif /* IEEE_MODE_CONF_RSSI_THRESHOLD */
/*---------------------------------------------------------------------------*/
#define STATUS_CRC_OK 0x80
#define STATUS_CORRELATION 0x7f
/*---------------------------------------------------------------------------*/
/* Data entry status field constants */
#define DATA_ENTRY_STATUS_PENDING 0x00 /* Not in use by the Radio CPU */
#define DATA_ENTRY_STATUS_ACTIVE 0x01 /* Open for r/w by the radio CPU */
@ -186,6 +190,35 @@ static const output_config_t output_power[] = {
/* Default TX Power - position in output_power[] */
const output_config_t *tx_power_current = &output_power[0];
/*---------------------------------------------------------------------------*/
static volatile int8_t last_rssi = 0;
static volatile uint8_t last_corr_lqi = 0;
extern int32_t rat_offset;
/*---------------------------------------------------------------------------*/
/* SFD timestamp in RTIMER ticks */
static volatile uint32_t last_packet_timestamp = 0;
/* SFD timestamp in RAT ticks (but 64 bits) */
static uint64_t last_rat_timestamp64 = 0;
/* For RAT overflow handling */
static struct ctimer rat_overflow_timer;
static uint32_t rat_overflow_counter = 0;
static rtimer_clock_t last_rat_overflow = 0;
/* RAT has 32-bit register, overflows once 18 minutes */
#define RAT_RANGE 4294967296ull
/* approximate value */
#define RAT_OVERFLOW_PERIOD_SECONDS (60 * 18)
/* XXX: don't know what exactly is this, looks like the time to Tx 3 octets */
#define TIMESTAMP_OFFSET -(USEC_TO_RADIO(32 * 3) - 1) /* -95.75 usec */
/*---------------------------------------------------------------------------*/
/* Are we currently in poll mode? */
static uint8_t poll_mode = 0;
static rfc_CMD_IEEE_MOD_FILT_t filter_cmd;
/*---------------------------------------------------------------------------*/
/*
* Buffers used to send commands to the RF core (generic and IEEE commands).
* Some of those buffers are re-usable, some are not.
@ -202,7 +235,7 @@ static uint8_t cmd_ieee_rx_buf[RF_CMD_BUFFER_SIZE] CC_ALIGN(4);
#define DATA_ENTRY_LENSZ_BYTE 1
#define DATA_ENTRY_LENSZ_WORD 2 /* 2 bytes */
#define RX_BUF_SIZE 140
#define RX_BUF_SIZE 144
/* Four receive buffers entries with room for 1 IEEE802.15.4 frame in each */
static uint8_t rx_buf_0[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_1[RX_BUF_SIZE] CC_ALIGN(4);
@ -544,7 +577,7 @@ init_rf_params(void)
cmd->rxConfig.bAppendRssi = 1;
cmd->rxConfig.bAppendCorrCrc = 1;
cmd->rxConfig.bAppendSrcInd = 0;
cmd->rxConfig.bAppendTimestamp = 0;
cmd->rxConfig.bAppendTimestamp = 1;
cmd->pRxQ = &rx_data_queue;
cmd->pOutput = (rfc_ieeeRxOutput_t *)rf_stats;
@ -647,13 +680,14 @@ rx_off(void)
if(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == IEEE_DONE_STOPPED ||
RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == IEEE_DONE_ABORT) {
/* Stopped gracefully */
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
ret = RF_CORE_CMD_OK;
} else {
PRINTF("RX off: BG status=0x%04x\n", RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf));
ret = RF_CORE_CMD_ERROR;
}
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
return ret;
}
/*---------------------------------------------------------------------------*/
@ -712,6 +746,55 @@ static const rf_core_primary_mode_t mode_ieee = {
soft_on,
};
/*---------------------------------------------------------------------------*/
static void
check_rat_overflow(bool first_time)
{
static uint32_t last_value;
uint32_t current_value;
uint8_t interrupts_enabled;
interrupts_enabled = ti_lib_int_master_disable();
if(first_time) {
last_value = HWREG(RFC_RAT_BASE + RATCNT);
} else {
current_value = HWREG(RFC_RAT_BASE + RATCNT);
if(current_value + RAT_RANGE / 4 < last_value) {
/* overflow detected */
last_rat_overflow = RTIMER_NOW();
rat_overflow_counter++;
}
last_value = current_value;
}
if(interrupts_enabled) {
ti_lib_int_master_enable();
}
}
/*---------------------------------------------------------------------------*/
static void
handle_rat_overflow(void *unused)
{
uint8_t was_off = 0;
if(!rf_is_on()) {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("overflow: on() failed\n");
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
handle_rat_overflow, NULL);
return;
}
}
check_rat_overflow(false);
if(was_off) {
off();
}
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
handle_rat_overflow, NULL);
}
/*---------------------------------------------------------------------------*/
static int
init(void)
{
@ -745,6 +828,10 @@ init(void)
rf_core_primary_mode_register(&mode_ieee);
check_rat_overflow(true);
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
handle_rat_overflow, NULL);
process_start(&rf_core_process, NULL);
return 1;
}
@ -768,6 +855,7 @@ transmit(unsigned short transmit_len)
uint8_t tx_active = 0;
rtimer_clock_t t0;
volatile rfc_CMD_IEEE_TX_t cmd;
uint8_t interrupts_enabled;
if(!rf_is_on()) {
was_off = 1;
@ -805,8 +893,19 @@ transmit(unsigned short transmit_len)
cmd.payloadLen = transmit_len;
cmd.pPayload = &tx_buf[TX_BUF_HDR_LEN];
cmd.startTime = 0;
cmd.startTrigger.triggerType = TRIG_NOW;
/* XXX: there seems to be no function that gets interrupt state w/o changing it */
interrupts_enabled = ti_lib_int_master_disable();
if(interrupts_enabled) {
ti_lib_int_master_enable();
}
/* Enable the LAST_FG_COMMAND_DONE interrupt, which will wake us up */
rf_core_cmd_done_en(true);
if(interrupts_enabled) {
rf_core_cmd_done_en(true, poll_mode);
}
ret = rf_core_send_cmd((uint32_t)&cmd, &cmd_status);
@ -818,7 +917,14 @@ transmit(unsigned short transmit_len)
/* Idle away while the command is running */
while((cmd.status & RF_CORE_RADIO_OP_MASKED_STATUS)
== RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING) {
lpm_sleep();
/* Note: for now sleeping while Tx'ing in polling mode is disabled.
* To enable it:
* 1) make the `lpm_sleep()` call here unconditional;
* 2) change the radio ISR priority to allow radio ISR to interrupt rtimer ISR.
*/
if(interrupts_enabled) {
lpm_sleep();
}
}
stat = cmd.status;
@ -848,12 +954,13 @@ transmit(unsigned short transmit_len)
ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
/*
* Disable LAST_FG_COMMAND_DONE interrupt. We don't really care about it
* except when we are transmitting
*/
rf_core_cmd_done_dis();
if(interrupts_enabled) {
/*
* Disable LAST_FG_COMMAND_DONE interrupt. We don't really care about it
* except when we are transmitting
*/
rf_core_cmd_done_dis(poll_mode);
}
if(was_off) {
off();
@ -880,13 +987,48 @@ release_data_entry(void)
/* Set status to 0 "Pending" in element */
entry->status = DATA_ENTRY_STATUS_PENDING;
rx_read_entry = entry->pNextEntry;
}/*---------------------------------------------------------------------------*/
}
/*---------------------------------------------------------------------------*/
static uint32_t
calc_last_packet_timestamp(uint32_t rat_timestamp)
{
uint64_t rat_timestamp64;
uint32_t adjusted_overflow_counter = rat_overflow_counter;
/* if the timestamp is large and the last oveflow was recently,
assume that the timestamp refers to the time before the overflow */
if(rat_timestamp > (uint32_t)(RAT_RANGE * 3 / 4)) {
if(RTIMER_CLOCK_LT(RTIMER_NOW(),
last_rat_overflow + RAT_OVERFLOW_PERIOD_SECONDS * RTIMER_SECOND / 4)) {
adjusted_overflow_counter--;
}
}
/* add the overflowed time to the timestamp */
rat_timestamp64 = rat_timestamp + RAT_RANGE * adjusted_overflow_counter;
/* correct timestamp so that it refers to the end of the SFD */
rat_timestamp64 += TIMESTAMP_OFFSET;
last_rat_timestamp64 = rat_timestamp64 - rat_offset;
return RADIO_TO_RTIMER(rat_timestamp64 - rat_offset);
}
/*---------------------------------------------------------------------------*/
static int
read_frame(void *buf, unsigned short buf_len)
{
int8_t rssi;
int len = 0;
rfc_dataEntryGeneral_t *entry = (rfc_dataEntryGeneral_t *)rx_read_entry;
uint32_t rat_timestamp;
if(rf_is_on()) {
check_rat_overflow(false);
}
/* wait for entry to become finished */
rtimer_clock_t t0 = RTIMER_NOW();
while(entry->status == DATA_ENTRY_STATUS_BUSY
&& RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (RTIMER_SECOND / 250)));
if(entry->status != DATA_ENTRY_STATUS_FINISHED) {
/* No available data */
@ -901,7 +1043,7 @@ read_frame(void *buf, unsigned short buf_len)
return 0;
}
len = rx_read_entry[8] - 4;
len = rx_read_entry[8] - 8;
if(len > buf_len) {
PRINTF("RF: too long\n");
@ -913,9 +1055,21 @@ read_frame(void *buf, unsigned short buf_len)
memcpy(buf, (char *)&rx_read_entry[9], len);
rssi = (int8_t)rx_read_entry[9 + len + 2];
last_rssi = (int8_t)rx_read_entry[9 + len + 2];
last_corr_lqi = (uint8_t)rx_read_entry[9 + len + 2] & STATUS_CORRELATION;
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rssi);
/* get the timestamp */
memcpy(&rat_timestamp, (char *)rx_read_entry + 9 + len + 4, 4);
last_packet_timestamp = calc_last_packet_timestamp(rat_timestamp);
if(!poll_mode) {
/* Not in poll mode: packetbuf should not be accessed in interrupt context.
* In poll mode, the last packet RSSI and link quality can be obtained through
* RADIO_PARAM_LAST_RSSI and RADIO_PARAM_LAST_LINK_QUALITY */
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, last_rssi);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, last_corr_lqi);
}
RIMESTATS_ADD(llrx);
release_data_entry();
@ -983,9 +1137,7 @@ channel_clear(void)
static int
receiving_packet(void)
{
int ret = 0;
uint8_t cca_info;
uint8_t was_off = 0;
/*
* If we are in the middle of a BLE operation, we got called by ContikiMAC
@ -1035,7 +1187,9 @@ pending_packet(void)
do {
if(entry->status == DATA_ENTRY_STATUS_FINISHED) {
rv = 1;
process_poll(&rf_core_process);
if(!poll_mode) {
process_poll(&rf_core_process);
}
}
entry = (rfc_dataEntry_t *)entry->pNextEntry;
@ -1076,7 +1230,7 @@ on(void)
init_rx_buffers();
rf_core_setup_interrupts();
rf_core_setup_interrupts(poll_mode);
/*
* Trigger a switch to the XOSC, so that we can subsequently use the RF FS
@ -1162,6 +1316,9 @@ get_value(radio_param_t param, radio_value_t *value)
if(cmd->frameFiltOpt.autoAckEn) {
*value |= RADIO_RX_MODE_AUTOACK;
}
if(poll_mode) {
*value |= RADIO_RX_MODE_POLL_MODE;
}
return RADIO_RESULT_OK;
case RADIO_PARAM_TXPOWER:
@ -1222,6 +1379,7 @@ set_value(radio_param_t param, radio_value_t value)
return RADIO_RESULT_INVALID_VALUE;
}
/* Note: this return may lead to long periods when RAT and RTC are not resynchronized */
if(cmd->channel == (uint8_t)value) {
/* We already have that very same channel configured.
* Nothing to do here. */
@ -1239,7 +1397,7 @@ set_value(radio_param_t param, radio_value_t value)
case RADIO_PARAM_RX_MODE:
{
if(value & ~(RADIO_RX_MODE_ADDRESS_FILTER |
RADIO_RX_MODE_AUTOACK)) {
RADIO_RX_MODE_AUTOACK | RADIO_RX_MODE_POLL_MODE)) {
return RADIO_RESULT_INVALID_VALUE;
}
@ -1252,6 +1410,8 @@ set_value(radio_param_t param, radio_value_t value)
cmd->frameFiltOpt.bPendDataReqOnly = 0;
cmd->frameFiltOpt.bPanCoord = 0;
cmd->frameFiltOpt.bStrictLenFilter = 0;
poll_mode = (value & RADIO_RX_MODE_POLL_MODE) != 0;
break;
}
case RADIO_PARAM_TXPOWER:
@ -1269,30 +1429,28 @@ set_value(radio_param_t param, radio_value_t value)
return RADIO_RESULT_NOT_SUPPORTED;
}
/* If we reach here we had no errors. Apply new settings */
/* If off, the new configuration will be applied the next time radio is started */
if(!rf_is_on()) {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("set_value: on() failed (2)\n");
return RADIO_RESULT_ERROR;
}
return RADIO_RESULT_OK;
}
/* If we reach here we had no errors. Apply new settings */
if(rx_off() != RF_CORE_CMD_OK) {
PRINTF("set_value: rx_off() failed\n");
rv = RADIO_RESULT_ERROR;
}
/* Restart the radio timer (RAT).
This causes resynchronization between RAT and RTC: useful for TSCH. */
rf_core_restart_rat();
check_rat_overflow(false);
if(rx_on() != RF_CORE_CMD_OK) {
PRINTF("set_value: rx_on() failed\n");
rv = RADIO_RESULT_ERROR;
}
/* If we were off, turn back off */
if(was_off) {
off();
}
return rv;
}
/*---------------------------------------------------------------------------*/
@ -1318,13 +1476,22 @@ get_object(radio_param_t param, void *dest, size_t size)
return RADIO_RESULT_OK;
}
if(param == RADIO_PARAM_LAST_PACKET_TIMESTAMP) {
if(size != sizeof(rtimer_clock_t) || !dest) {
return RADIO_RESULT_INVALID_VALUE;
}
*(rtimer_clock_t *)dest = last_packet_timestamp;
return RADIO_RESULT_OK;
}
return RADIO_RESULT_NOT_SUPPORTED;
}
/*---------------------------------------------------------------------------*/
static radio_result_t
set_object(radio_param_t param, const void *src, size_t size)
{
uint8_t was_off = 0;
radio_result_t rv;
int i;
uint8_t *dst;
@ -1341,12 +1508,9 @@ set_object(radio_param_t param, const void *src, size_t size)
dst[i] = ((uint8_t *)src)[7 - i];
}
/* If off, the new configuration will be applied the next time radio is started */
if(!rf_is_on()) {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("set_object: on() failed\n");
return RADIO_RESULT_ERROR;
}
return RADIO_RESULT_OK;
}
if(rx_off() != RF_CORE_CMD_OK) {
@ -1359,11 +1523,6 @@ set_object(radio_param_t param, const void *src, size_t size)
rv = RADIO_RESULT_ERROR;
}
/* If we were off, turn back off */
if(was_off) {
off();
}
return rv;
}
return RADIO_RESULT_NOT_SUPPORTED;

View file

@ -683,7 +683,7 @@ transmit(unsigned short transmit_len)
rx_off_prop();
/* Enable the LAST_COMMAND_DONE interrupt to wake us up */
rf_core_cmd_done_en(false);
rf_core_cmd_done_en(false, false);
ret = rf_core_send_cmd((uint32_t)cmd_tx_adv, &cmd_status);
@ -728,7 +728,7 @@ transmit(unsigned short transmit_len)
* Disable LAST_FG_COMMAND_DONE interrupt. We don't really care about it
* except when we are transmitting
*/
rf_core_cmd_done_dis();
rf_core_cmd_done_dis(false);
/* Workaround. Set status to IDLE */
cmd_tx_adv->status = RF_CORE_RADIO_OP_STATUS_IDLE;
@ -933,7 +933,7 @@ on(void)
}
}
rf_core_setup_interrupts();
rf_core_setup_interrupts(false);
/*
* Trigger a switch to the XOSC, so that we can subsequently use the RF FS

View file

@ -92,6 +92,8 @@
#define ENABLED_IRQS (RX_FRAME_IRQ | ERROR_IRQ)
#endif
#define ENABLED_IRQS_POLL_MODE (ENABLED_IRQS & ~(RX_FRAME_IRQ | ERROR_IRQ))
#define cc26xx_rf_cpe0_isr RFCCPE0IntHandler
#define cc26xx_rf_cpe1_isr RFCCPE1IntHandler
/*---------------------------------------------------------------------------*/
@ -101,6 +103,10 @@ static rfc_radioOp_t *last_radio_op = NULL;
/* A struct holding pointers to the primary mode's abort() and restore() */
static const rf_core_primary_mode_t *primary_mode = NULL;
/*---------------------------------------------------------------------------*/
/* Radio timer (RAT) offset as compared to the rtimer counter (RTC) */
int32_t rat_offset = 0;
static bool rat_offset_known = false;
/*---------------------------------------------------------------------------*/
PROCESS(rf_core_process, "CC13xx / CC26xx RF driver");
/*---------------------------------------------------------------------------*/
#define RF_CORE_CLOCKS_MASK (RFC_PWR_PWMCLKEN_RFC_M | RFC_PWR_PWMCLKEN_CPE_M \
@ -265,6 +271,66 @@ rf_core_power_up()
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_start_rat(void)
{
uint32_t cmd_status;
rfc_CMD_SYNC_START_RAT_t cmd_start;
/* Start radio timer (RAT) */
rf_core_init_radio_op((rfc_radioOp_t *)&cmd_start, sizeof(cmd_start), CMD_SYNC_START_RAT);
/* copy the value and send back */
cmd_start.rat0 = rat_offset;
if(rf_core_send_cmd((uint32_t)&cmd_start, &cmd_status) != RF_CORE_CMD_OK) {
PRINTF("rf_core_get_rat_rtc_offset: SYNC_START_RAT fail, CMDSTA=0x%08lx\n",
cmd_status);
return RF_CORE_CMD_ERROR;
}
/* Wait until done (?) */
if(rf_core_wait_cmd_done(&cmd_start) != RF_CORE_CMD_OK) {
PRINTF("rf_core_cmd_ok: SYNC_START_RAT wait, CMDSTA=0x%08lx, status=0x%04x\n",
cmd_status, cmd_start.status);
return RF_CORE_CMD_ERROR;
}
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_stop_rat(void)
{
rfc_CMD_SYNC_STOP_RAT_t cmd_stop;
uint32_t cmd_status;
rf_core_init_radio_op((rfc_radioOp_t *)&cmd_stop, sizeof(cmd_stop), CMD_SYNC_STOP_RAT);
int ret = rf_core_send_cmd((uint32_t)&cmd_stop, &cmd_status);
if(ret != RF_CORE_CMD_OK) {
PRINTF("rf_core_get_rat_rtc_offset: SYNC_STOP_RAT fail, ret %d CMDSTA=0x%08lx\n",
ret, cmd_status);
return ret;
}
/* Wait until done */
ret = rf_core_wait_cmd_done(&cmd_stop);
if(ret != RF_CORE_CMD_OK) {
PRINTF("rf_core_cmd_ok: SYNC_STOP_RAT wait, CMDSTA=0x%08lx, status=0x%04x\n",
cmd_status, cmd_stop.status);
return ret;
}
if(!rat_offset_known) {
/* save the offset, but only if this is the first time */
rat_offset_known = true;
rat_offset = cmd_stop.rat0;
}
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
void
rf_core_power_down()
{
@ -280,6 +346,8 @@ rf_core_power_down()
fs_powerdown();
}
rf_core_stop_rat();
/* Shut down the RFCORE clock domain in the MCU VD */
ti_lib_prcm_domain_disable(PRCM_DOMAIN_RFCORE);
ti_lib_prcm_load_set();
@ -329,22 +397,6 @@ rf_core_set_modesel()
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_start_rat()
{
uint32_t cmd_status;
/* Start radio timer (RAT) */
if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_START_RAT), &cmd_status)
!= RF_CORE_CMD_OK) {
PRINTF("rf_core_apply_patches: START_RAT fail, CMDSTA=0x%08lx\n",
cmd_status);
return RF_CORE_CMD_ERROR;
}
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_boot()
{
if(rf_core_power_up() != RF_CORE_CMD_OK) {
@ -366,10 +418,31 @@ rf_core_boot()
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_restart_rat(void)
{
if(rf_core_stop_rat() != RF_CORE_CMD_OK) {
PRINTF("rf_core_restart_rat: rf_core_stop_rat() failed\n");
return RF_CORE_CMD_ERROR;
}
if(rf_core_start_rat() != RF_CORE_CMD_OK) {
PRINTF("rf_core_restart_rat: rf_core_start_rat() failed\n");
rf_core_power_down();
return RF_CORE_CMD_ERROR;
}
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
void
rf_core_setup_interrupts()
rf_core_setup_interrupts(bool poll_mode)
{
bool interrupts_disabled;
const uint32_t enabled_irqs = poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
/* We are already turned on by the caller, so this should not happen */
if(!rf_core_is_accessible()) {
@ -384,7 +457,7 @@ rf_core_setup_interrupts()
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEISL) = ERROR_IRQ;
/* Acknowledge configured interrupts */
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = ENABLED_IRQS;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = enabled_irqs;
/* Clear interrupt flags, active low clear(?) */
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIFG) = 0x0;
@ -400,18 +473,20 @@ rf_core_setup_interrupts()
}
/*---------------------------------------------------------------------------*/
void
rf_core_cmd_done_en(bool fg)
rf_core_cmd_done_en(bool fg, bool poll_mode)
{
uint32_t irq = fg ? IRQ_LAST_FG_COMMAND_DONE : IRQ_LAST_COMMAND_DONE;
const uint32_t enabled_irqs = poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIFG) = ENABLED_IRQS;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = ENABLED_IRQS | irq;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIFG) = enabled_irqs;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = enabled_irqs | irq;
}
/*---------------------------------------------------------------------------*/
void
rf_core_cmd_done_dis()
rf_core_cmd_done_dis(bool poll_mode)
{
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = ENABLED_IRQS;
const uint32_t enabled_irqs = poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = enabled_irqs;
}
/*---------------------------------------------------------------------------*/
rfc_radioOp_t *

View file

@ -228,6 +228,9 @@ typedef struct rf_core_primary_mode_s {
#define RF_CORE_COMMAND_PROTOCOL_IEEE 0x2000
#define RF_CORE_COMMAND_PROTOCOL_PROP 0x3000
/*---------------------------------------------------------------------------*/
/* Radio timer register */
#define RATCNT 0x00000004
/*---------------------------------------------------------------------------*/
/* Make the main driver process visible to mode drivers */
PROCESS_NAME(rf_core_process);
/*---------------------------------------------------------------------------*/
@ -310,6 +313,24 @@ uint8_t rf_core_set_modesel(void);
*/
uint8_t rf_core_start_rat(void);
/**
* \brief Stop the CM0 RAT synchronously
* \return RF_CORE_CMD_OK or RF_CORE_CMD_ERROR
*
* This function is not strictly necessary, but through calling it it's possibly
* to learn the RAT / RTC offset, which useful to get accurate radio timestamps.
*/
uint8_t rf_core_stop_rat(void);
/**
* \brief Restart the CM0 RAT
* \return RF_CORE_CMD_OK or RF_CORE_CMD_ERROR
*
* This function restarts the CM0 RAT and therefore resynchornizes it with RTC.
* To achieve good timing accuracy, it should be called periodically.
*/
uint8_t rf_core_restart_rat(void);
/**
* \brief Boot the RF Core
* \return RF_CORE_CMD_OK or RF_CORE_CMD_ERROR
@ -327,19 +348,20 @@ uint8_t rf_core_boot(void);
/**
* \brief Setup RF core interrupts
*/
void rf_core_setup_interrupts(void);
void rf_core_setup_interrupts(bool poll_mode);
/**
* \brief Enable interrupt on command done.
* \param fg set true to enable irq on foreground command done and false for
* background commands or if not in ieee mode.
* \param poll_mode true if the driver is in poll mode
*
* This is used within TX routines in order to be able to sleep the CM3 and
* wake up after TX has finished
*
* \sa rf_core_cmd_done_dis()
*/
void rf_core_cmd_done_en(bool fg);
void rf_core_cmd_done_en(bool fg, bool poll_mode);
/**
* \brief Disable the LAST_CMD_DONE and LAST_FG_CMD_DONE interrupts.
@ -348,7 +370,7 @@ void rf_core_cmd_done_en(bool fg);
*
* \sa rf_core_cmd_done_en()
*/
void rf_core_cmd_done_dis(void);
void rf_core_cmd_done_dis(bool poll_mode);
/**
* \brief Returns a pointer to the most recent proto-dependent Radio Op