cpu/cc2538: Add RF driver
This commit is contained in:
parent
52ff326f69
commit
a2ba22dd0f
@ -4,4 +4,9 @@ MODULE = cpu
|
||||
# Add a list of subdirectories, that should also be built:
|
||||
DIRS = periph $(RIOTCPU)/cortexm_common
|
||||
|
||||
# cc2538_rf radio driver
|
||||
ifneq (,$(filter cc2538_rf,$(USEMODULE)))
|
||||
DIRS += radio
|
||||
endif
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
||||
|
||||
332
cpu/cc2538/include/cc2538_rf.h
Normal file
332
cpu/cc2538/include/cc2538_rf.h
Normal file
@ -0,0 +1,332 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd.
|
||||
* Copyright (C) 2015 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level radio driver for the CC2538
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*/
|
||||
|
||||
#ifndef CC2538_RF_H
|
||||
#define CC2538_RF_H
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "mutex.h"
|
||||
#include "net/netdev2.h"
|
||||
#include "net/netdev2/ieee802154.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define CC2538_AUTOCRC_LEN (2)
|
||||
#define CC2538_RF_FIFO_SIZE (128)
|
||||
#define CC2538_PACKET_LENGTH_SIZE (1)
|
||||
|
||||
#define CC2538_RF_MAX_DATA_LEN (CC2538_RF_FIFO_SIZE - CC2538_PACKET_LENGTH_SIZE)
|
||||
|
||||
#define CC2538_EUI64_LOCATION_PRI (0x00280028) /**< Primary EUI-64 address location */
|
||||
#define CC2538_EUI64_LOCATION_SEC (0x0027FFCC) /**< Secondary EUI-64 address location */
|
||||
|
||||
/* TODO: Move these to sys/include/net/ieee802154.h somehow */
|
||||
/* IEEE 802.15.4 defined constants (2.4 GHz logical channels) */
|
||||
#define IEEE802154_MIN_FREQ (2405) /**< Min. frequency (2405 MHz) */
|
||||
#define IEEE802154_MAX_FREQ (2480) /**< Max. frequency (2480 MHz) */
|
||||
|
||||
#define IEEE802154_MIN_CHANNEL (11) /**< Min. channel (2405 MHz) */
|
||||
#define IEEE802154_MAX_CHANNEL (26) /**< Max. channel (2480 MHz) */
|
||||
#define IEEE802154_CHANNEL_SPACING (5) /**< Channel spacing in MHz */
|
||||
|
||||
#define IEEE802154_CHAN2FREQ(chan) ( IEEE802154_MIN_FREQ + ((chan) - IEEE802154_MIN_CHANNEL) * IEEE802154_CHANNEL_SPACING )
|
||||
#define IEEE802154_FREQ2CHAN(freq) ( IEEE802154_MIN_CHANNEL + ((freq) - IEEE802154_MIN_FREQ) / IEEE802154_CHANNEL_SPACING )
|
||||
/* /TODO */
|
||||
|
||||
#define CC2538_MIN_FREQ (2394)
|
||||
#define CC2538_MAX_FREQ (2507)
|
||||
|
||||
#define CC2538_RF_POWER_DEFAULT (3) /**< Default output power in dBm */
|
||||
#define CC2538_RF_CHANNEL_DEFAULT (26U)
|
||||
#define CC2538_RF_PANID_DEFAULT (0x0023)
|
||||
|
||||
#define OUTPUT_POWER_MIN (-24) /**< Min output power in dBm */
|
||||
#define OUTPUT_POWER_MAX (7) /**< Max output power in dBm */
|
||||
#define NUM_POWER_LEVELS ( OUTPUT_POWER_MAX - OUTPUT_POWER_MIN + 1 )
|
||||
|
||||
#define RFCORE_ASSERT(expr) (void)( (expr) || RFCORE_ASSERT_failure(#expr, __FUNCTION__, __LINE__) )
|
||||
|
||||
#if DEVELHELP
|
||||
#define RFCORE_WAIT_UNTIL(expr) while (!(expr)) { \
|
||||
DEBUG("RFCORE_WAIT_UNTIL(%s) at line %u in %s()\n", #expr, __LINE__, __FUNCTION__); \
|
||||
thread_yield(); \
|
||||
}
|
||||
#else
|
||||
#define RFCORE_WAIT_UNTIL(expr) while (!(expr)) thread_yield()
|
||||
#endif
|
||||
|
||||
#define RFCORE_FLUSH_RECEIVE_FIFO() rfcore_strobe(ISFLUSHRX)
|
||||
|
||||
#define ABS_DIFF(x, y) ( ((x) < (y))? ((y) - (x)) : ((x) - (y)) )
|
||||
#define BOOLEAN(x) ( (x) != 0 )
|
||||
#define NOT(x) ( (x) == 0 )
|
||||
#define GET_BYTE(buffer, index) ( (unsigned char*)(buffer) )[index]
|
||||
|
||||
#define BIT(n) ( 1 << (n) )
|
||||
|
||||
enum {
|
||||
FSM_STATE_IDLE = 0,
|
||||
FSM_STATE_RX_CALIBRATION = 2,
|
||||
FSM_STATE_TX_CALIBRATION = 32,
|
||||
};
|
||||
|
||||
/*
|
||||
* @brief RFCORE_XREG_RFERRM bits
|
||||
*/
|
||||
enum {
|
||||
STROBE_ERR = BIT(6),
|
||||
TXUNDERF = BIT(5),
|
||||
TXOVERF = BIT(4),
|
||||
RXUNDERF = BIT(3),
|
||||
RXOVERF = BIT(2),
|
||||
RXABO = BIT(1),
|
||||
NLOCK = BIT(0),
|
||||
};
|
||||
|
||||
/*
|
||||
* @brief RFCORE_XREG_FRMCTRL0 bits
|
||||
*/
|
||||
enum {
|
||||
ENERGY_SCAN = BIT(4),
|
||||
AUTOACK = BIT(5),
|
||||
AUTOCRC = BIT(6),
|
||||
APPEND_DATA_MODE = BIT(7),
|
||||
};
|
||||
|
||||
/*
|
||||
* @brief RFCORE_XREG_RFIRQM0 / RFCORE_XREG_RFIRQF0 bits
|
||||
*/
|
||||
enum {
|
||||
ACT_UNUSED = BIT(0),
|
||||
SFD = BIT(1), /**< Start of frame event */
|
||||
FIFOP = BIT(2),
|
||||
SRC_MATCH_DONE = BIT(3),
|
||||
SRC_MATCH_FOUND = BIT(4),
|
||||
FRAME_ACCEPTED = BIT(5),
|
||||
RXPKTDONE = BIT(6), /**< End of frame event */
|
||||
RXMASKZERO = BIT(7),
|
||||
};
|
||||
|
||||
/* Values for use with CCTEST_OBSSELx registers: */
|
||||
#define OBSSEL_EN BIT(7)
|
||||
enum {
|
||||
rfc_obs_sig0 = 0,
|
||||
rfc_obs_sig1 = 1,
|
||||
rfc_obs_sig2 = 2,
|
||||
};
|
||||
|
||||
/* Values for RFCORE_XREG_RFC_OBS_CTRLx registers: */
|
||||
enum {
|
||||
constant_value_0 = 0x00,
|
||||
constant_value_1 = 0x01,
|
||||
rfc_sniff_data = 0x08,
|
||||
rfc_sniff_clk = 0x09,
|
||||
rssi_valid = 0x0c,
|
||||
demod_cca = 0x0d,
|
||||
sampled_cca = 0x0e,
|
||||
sfd_sync = 0x0f,
|
||||
tx_active = 0x10,
|
||||
rx_active = 0x11,
|
||||
ffctrl_fifo = 0x12,
|
||||
ffctrl_fifop = 0x13,
|
||||
packet_done = 0x14,
|
||||
rfc_xor_rand_i_q = 0x16,
|
||||
rfc_rand_q = 0x17,
|
||||
rfc_rand_i = 0x18,
|
||||
lock_status = 0x19,
|
||||
pa_pd = 0x20,
|
||||
lna_pd = 0x2a,
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Device descriptor for CC2538 transceiver
|
||||
*
|
||||
* @extends netdev2_ieee802154_t
|
||||
*/
|
||||
typedef struct {
|
||||
netdev2_ieee802154_t netdev; /**< netdev2 parent struct */
|
||||
uint8_t state; /**< current state of the radio */
|
||||
mutex_t mutex; /**< device access lock */
|
||||
} cc2538_rf_t;
|
||||
|
||||
/**
|
||||
* @brief IRQ handler for RF events
|
||||
*
|
||||
*/
|
||||
void _irq_handler(void);
|
||||
|
||||
/**
|
||||
* @brief Trigger a clear channel assessment
|
||||
*
|
||||
* @return True if channel is clear
|
||||
* @return False if channel is busy
|
||||
*/
|
||||
bool cc2538_channel_clear(void);
|
||||
|
||||
/**
|
||||
* @brief Get the configured long address of the device
|
||||
*
|
||||
* @return The currently set (8-byte) long address
|
||||
*/
|
||||
uint64_t cc2538_get_addr_long(void);
|
||||
|
||||
/**
|
||||
* @brief Get the configured short address of the device
|
||||
*
|
||||
* @return The currently set (2-byte) short address
|
||||
*/
|
||||
uint16_t cc2538_get_addr_short(void);
|
||||
|
||||
/**
|
||||
* @brief Get the primary (burned-in) EUI-64 of the device
|
||||
*
|
||||
* @return The primary EUI-64 of the device
|
||||
*/
|
||||
uint64_t cc2538_get_eui64_primary(void);
|
||||
|
||||
/**
|
||||
* @brief Get the configured channel number of the device
|
||||
*
|
||||
* @return The currently set channel number
|
||||
*/
|
||||
unsigned int cc2538_get_chan(void);
|
||||
|
||||
/**
|
||||
* @brief Check if device is in monitor (promiscuous) mode
|
||||
*
|
||||
* @return True if device is in monitor mode
|
||||
* @return False if device is not in monitor mode
|
||||
*/
|
||||
bool cc2538_get_monitor(void);
|
||||
|
||||
/**
|
||||
* @brief Get the configured PAN ID of the device
|
||||
*
|
||||
* @return The currently set PAN ID
|
||||
*/
|
||||
uint16_t cc2538_get_pan(void);
|
||||
|
||||
/**
|
||||
* @brief Get the configured transmission power of the device
|
||||
*
|
||||
* @return The currently configured transmission power in dBm
|
||||
*/
|
||||
int cc2538_get_tx_power(void);
|
||||
|
||||
/**
|
||||
* @brief Initialise the CC2538 radio hardware
|
||||
*
|
||||
*/
|
||||
void cc2538_init(void);
|
||||
|
||||
/**
|
||||
* @brief Check if device is active
|
||||
*
|
||||
* @return True if device is active
|
||||
* @return False if device is not active
|
||||
*/
|
||||
bool cc2538_is_on(void);
|
||||
|
||||
/**
|
||||
* @brief Deactivate the CC2538 radio device
|
||||
*
|
||||
*/
|
||||
void cc2538_off(void);
|
||||
|
||||
/**
|
||||
* @brief Activate the CC2538 radio device
|
||||
*
|
||||
*/
|
||||
bool cc2538_on(void);
|
||||
|
||||
/**
|
||||
* @brief Setup a CC2538 radio device for use with netdev
|
||||
*
|
||||
* @param[out] dev Device descriptor
|
||||
*/
|
||||
void cc2538_setup(cc2538_rf_t *dev);
|
||||
|
||||
/**
|
||||
* @brief Set the short address of the device
|
||||
*
|
||||
* @param[in] addr (2-byte) short address to set
|
||||
*/
|
||||
void cc2538_set_addr_short(uint16_t addr);
|
||||
|
||||
/**
|
||||
* @brief Set the long address of the device
|
||||
*
|
||||
* @param[in] addr (8-byte) short address to set
|
||||
*/
|
||||
void cc2538_set_addr_long(uint64_t addr);
|
||||
|
||||
/**
|
||||
* @brief Set the channel number of the device
|
||||
*
|
||||
* @param[in] chan Channel number to set
|
||||
*/
|
||||
void cc2538_set_chan(unsigned int chan);
|
||||
|
||||
/**
|
||||
* @brief Set the frequency of the device
|
||||
*
|
||||
* @param[in] MHz Frequency to set in MHz
|
||||
*/
|
||||
void cc2538_set_freq(unsigned int MHz);
|
||||
|
||||
/**
|
||||
* @brief Enable/disable monitor (promiscuous) mode for the device
|
||||
*
|
||||
* @param[in] mode True for enable, false for disable
|
||||
*/
|
||||
void cc2538_set_monitor(bool mode);
|
||||
|
||||
/**
|
||||
* @brief Set the PAN ID of the device
|
||||
*
|
||||
* @param[in] pan PAN ID to set
|
||||
*/
|
||||
void cc2538_set_pan(uint16_t pan);
|
||||
|
||||
/**
|
||||
* @brief Set the state of the device
|
||||
*
|
||||
* @param[out] dev Device descriptor
|
||||
* @param[in] state State to set device to
|
||||
*/
|
||||
void cc2538_set_state(cc2538_rf_t *dev, netopt_state_t state);
|
||||
|
||||
/**
|
||||
* @brief Set the transmission power for the device
|
||||
*
|
||||
* @param[in] dBm Transmission power to set in dBm
|
||||
*/
|
||||
void cc2538_set_tx_power(int dBm);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CC2538_RF_H */
|
||||
/** @} */
|
||||
104
cpu/cc2538/include/cc2538_rf_internal.h
Normal file
104
cpu/cc2538/include/cc2538_rf_internal.h
Normal file
@ -0,0 +1,104 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Internal interfaces for the cc2538_rf driver
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
*/
|
||||
|
||||
#ifndef CC2538_RF_INTERNAL_H_
|
||||
#define CC2538_RF_INTERNAL_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define CC2538_RX_FIFO_ADDR 0x40088000
|
||||
#define CC2538_TX_FIFO_ADDR 0x40088200
|
||||
|
||||
/**
|
||||
* @brief Read a single byte from the RX FIFO
|
||||
*
|
||||
* This function will return the first currently unread byte
|
||||
* from the RX FIFO, and advance the FIFO pointer by one. Hence,
|
||||
* subsequent calls to this function will return subsequent bytes
|
||||
* from the RX FIFO.
|
||||
*
|
||||
* @return The first currently unread byte from the RX FIFO
|
||||
*/
|
||||
uint_fast8_t rfcore_read_byte(void);
|
||||
|
||||
/**
|
||||
* @brief Peek a single byte from the RX FIFO
|
||||
*
|
||||
* Peeking, as opposed to reading, a byte from the RX FIFO
|
||||
* will not advance the FIFO pointer. Further, bytes may be
|
||||
* read from any position in the FIFO by providing an index.
|
||||
*
|
||||
* @param[in] idx The index of the byte to peek
|
||||
*
|
||||
* @return The byte at index idx
|
||||
*/
|
||||
uint_fast8_t rfcore_peek_rx_fifo(int idx);
|
||||
|
||||
/**
|
||||
* @brief Read the remaining unread data from the RX FIFO
|
||||
*
|
||||
* @param[out] buf The buffer to read the data into
|
||||
* @param[in] len The maximum length of the buffer
|
||||
*/
|
||||
void rfcore_read_fifo(void *buf, uint_fast8_t len);
|
||||
|
||||
/**
|
||||
* @brief Issue a command strobe from the CPU to the radio
|
||||
*
|
||||
* @param[in] instr The instruction to issue
|
||||
*/
|
||||
void rfcore_strobe(uint_fast8_t instr);
|
||||
|
||||
/**
|
||||
* @brief Write a single byte to the next index of the TX FIFO
|
||||
*
|
||||
* @param[in] byte The byte to write
|
||||
*/
|
||||
void rfcore_write_byte(uint_fast8_t byte);
|
||||
|
||||
/**
|
||||
* @brief Poke a single byte in the TX FIFO
|
||||
*
|
||||
* Poking, as opposed to writing, a byte to the TX FIFO
|
||||
* will not advance the FIFO pointer. Further, bytes may be
|
||||
* written to any position in the FIFO by providing an index.
|
||||
*
|
||||
* @param[in] idx The index of the byte to write to
|
||||
* @param[in] byte The byte to write
|
||||
*/
|
||||
void rfcore_poke_tx_fifo(int idx, uint_fast8_t byte);
|
||||
|
||||
/**
|
||||
* @brief Write a string of bytes to the TX FIFO
|
||||
*
|
||||
* @param[in] buf The buffer containing the data to write
|
||||
* @param[in] len The length of the data to write
|
||||
*/
|
||||
void rfcore_write_fifo(const void *buf, uint_fast8_t len);
|
||||
|
||||
bool RFCORE_ASSERT_failure(const char *expr, const char *func, int line);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CC2538_RF_INTERNAL_H_ */
|
||||
/** @} */
|
||||
39
cpu/cc2538/include/cc2538_rf_netdev.h
Normal file
39
cpu/cc2538/include/cc2538_rf_netdev.h
Normal file
@ -0,0 +1,39 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Netdev interface to CC2538 radio driver
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
*/
|
||||
|
||||
#ifndef CC2538_RF_NETDEV_H_
|
||||
#define CC2538_RF_NETDEV_H_
|
||||
|
||||
#include "net/netdev2.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Reference to the netdev device driver struct
|
||||
*/
|
||||
extern const netdev2_driver_t cc2538_rf_driver;
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CC2538_RF_NETDEV_H_ */
|
||||
/** @} */
|
||||
@ -54,7 +54,17 @@ typedef struct {
|
||||
cc2538_reg_t FFSM_SHORT_ADDR0; /**< RF Local address information */
|
||||
cc2538_reg_t FFSM_SHORT_ADDR1; /**< RF Local address information */
|
||||
cc2538_reg_t RESERVED1[10]; /**< Reserved bytes */
|
||||
cc2538_reg_t XREG_FRMFILT0; /**< RF Frame Filter 0 */
|
||||
|
||||
union {
|
||||
cc2538_reg_t XREG_FRMFILT0; /**< RF Frame Filter 0 */
|
||||
struct {
|
||||
cc2538_reg_t FRAME_FILTER_EN : 1;
|
||||
cc2538_reg_t PAN_COORDINATOR : 1;
|
||||
cc2538_reg_t MAX_FRAME_VERSION: 2;
|
||||
cc2538_reg_t RESERVED : 28;
|
||||
} XREG_FRMFILT0bits;
|
||||
};
|
||||
|
||||
cc2538_reg_t XREG_FRMFILT1; /**< RF Frame Filter 1 */
|
||||
cc2538_reg_t XREG_SRCMATCH; /**< RF Source address matching and pending bits */
|
||||
cc2538_reg_t XREG_SRCSHORTEN0; /**< RF Short address matching */
|
||||
@ -63,7 +73,20 @@ typedef struct {
|
||||
cc2538_reg_t XREG_SRCEXTEN0; /**< RF Extended address matching */
|
||||
cc2538_reg_t XREG_SRCEXTEN1; /**< RF Extended address matching */
|
||||
cc2538_reg_t XREG_SRCEXTEN2; /**< RF Extended address matching */
|
||||
cc2538_reg_t XREG_FRMCTRL0; /**< RF Frame handling */
|
||||
|
||||
union {
|
||||
cc2538_reg_t XREG_FRMCTRL0; /**< RF Frame handling */
|
||||
struct {
|
||||
cc2538_reg_t TX_MODE : 2;
|
||||
cc2538_reg_t RX_MODE : 2;
|
||||
cc2538_reg_t ENERGY_SCAN : 1;
|
||||
cc2538_reg_t AUTOACK : 1;
|
||||
cc2538_reg_t AUTOCRC : 1;
|
||||
cc2538_reg_t APPEND_DATA_MODE : 1;
|
||||
cc2538_reg_t RESERVED : 24;
|
||||
} XREG_FRMCTRL0bits;
|
||||
};
|
||||
|
||||
cc2538_reg_t XREG_FRMCTRL1; /**< RF Frame handling */
|
||||
cc2538_reg_t XREG_RXENABLE; /**< RF RX enabling */
|
||||
cc2538_reg_t XREG_RXMASKSET; /**< RF RX enabling */
|
||||
@ -72,8 +95,32 @@ typedef struct {
|
||||
cc2538_reg_t XREG_FREQCTRL; /**< RF Controls the RF frequency */
|
||||
cc2538_reg_t XREG_TXPOWER; /**< RF Controls the output power */
|
||||
cc2538_reg_t XREG_TXCTRL; /**< RF Controls the TX settings */
|
||||
cc2538_reg_t XREG_FSMSTAT0; /**< RF Radio status register */
|
||||
cc2538_reg_t XREG_FSMSTAT1; /**< RF Radio status register */
|
||||
|
||||
union {
|
||||
cc2538_reg_t XREG_FSMSTAT0; /**< RF Radio status register */
|
||||
struct {
|
||||
cc2538_reg_t FSM_FFCTRL_STATE : 6;
|
||||
cc2538_reg_t CAL_RUNNING : 1;
|
||||
cc2538_reg_t CAL_DONE : 1;
|
||||
cc2538_reg_t RESERVED : 24;
|
||||
} XREG_FSMSTAT0bits;
|
||||
};
|
||||
|
||||
union {
|
||||
cc2538_reg_t XREG_FSMSTAT1; /**< RF Radio status register */
|
||||
struct {
|
||||
cc2538_reg_t RX_ACTIVE : 1;
|
||||
cc2538_reg_t TX_ACTIVE : 1;
|
||||
cc2538_reg_t LOCK_STATUS : 1;
|
||||
cc2538_reg_t SAMPLED_CCA : 1;
|
||||
cc2538_reg_t CCA : 1;
|
||||
cc2538_reg_t SFD : 1;
|
||||
cc2538_reg_t FIFOP : 1;
|
||||
cc2538_reg_t FIFO : 1;
|
||||
cc2538_reg_t RESERVED : 24;
|
||||
} XREG_FSMSTAT1bits;
|
||||
};
|
||||
|
||||
cc2538_reg_t XREG_FIFOPCTRL; /**< RF FIFOP threshold */
|
||||
cc2538_reg_t XREG_FSMCTRL; /**< RF FSM options */
|
||||
cc2538_reg_t XREG_CCACTRL0; /**< RF CCA threshold */
|
||||
|
||||
3
cpu/cc2538/radio/Makefile
Normal file
3
cpu/cc2538/radio/Makefile
Normal file
@ -0,0 +1,3 @@
|
||||
MODULE = cc2538_rf
|
||||
|
||||
include $(RIOTBASE)/Makefile.base
|
||||
180
cpu/cc2538/radio/cc2538_rf.c
Normal file
180
cpu/cc2538/radio/cc2538_rf.c
Normal file
@ -0,0 +1,180 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd.
|
||||
* Copyright (C) 2015 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level radio driver for the CC2538
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "periph_conf.h"
|
||||
|
||||
#include "cc2538_rf.h"
|
||||
#include "cc2538_rf_netdev.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
typedef struct {
|
||||
cc2538_reg_t *reg_addr;
|
||||
uint32_t value;
|
||||
} init_pair_t;
|
||||
|
||||
static const init_pair_t init_table[] = {
|
||||
{&SYS_CTRL_RCGCRFC, 0x01 },
|
||||
{&SYS_CTRL_SCGCRFC, 0x01 },
|
||||
{&SYS_CTRL_DCGCRFC, 0x01 },
|
||||
{&RFCORE_XREG_CCACTRL0, 0xf8 },
|
||||
{&RFCORE_XREG_TXFILTCFG, 0x09 },
|
||||
{&RFCORE_XREG_AGCCTRL1, 0x15 },
|
||||
{&ANA_REGS_IVCTRL, 0x0b },
|
||||
{&RFCORE_XREG_MDMTEST1, 0x08 },
|
||||
{&RFCORE_XREG_FSCAL1, 0x01 },
|
||||
{&RFCORE_XREG_RXCTRL, 0x3f },
|
||||
{&RFCORE_XREG_MDMCTRL1, 0x14 },
|
||||
{&RFCORE_XREG_ADCTEST0, 0x10 },
|
||||
{&RFCORE_XREG_ADCTEST1, 0x0e },
|
||||
{&RFCORE_XREG_ADCTEST2, 0x03 },
|
||||
{&RFCORE_XREG_CSPT, 0xff },
|
||||
{&RFCORE_XREG_MDMCTRL0, 0x85 },
|
||||
{&RFCORE_XREG_FSCTRL, 0x55 },
|
||||
{&RFCORE_XREG_FRMCTRL0, AUTOCRC | AUTOACK },
|
||||
{&RFCORE_XREG_FRMCTRL1, 0x00 },
|
||||
{&RFCORE_XREG_SRCMATCH, 0x00 },
|
||||
{&RFCORE_XREG_FIFOPCTRL, CC2538_RF_MAX_DATA_LEN },
|
||||
{&RFCORE_XREG_RFIRQM0, FIFOP | RXPKTDONE },
|
||||
{&RFCORE_XREG_RFERRM, STROBE_ERR | TXUNDERF | TXOVERF | RXUNDERF | RXOVERF | NLOCK},
|
||||
{NULL, 0},
|
||||
};
|
||||
|
||||
bool cc2538_channel_clear(void)
|
||||
{
|
||||
if (RFCORE->XREG_FSMSTAT0bits.FSM_FFCTRL_STATE == FSM_STATE_IDLE) {
|
||||
bool result;
|
||||
cc2538_on();
|
||||
RFCORE_WAIT_UNTIL(RFCORE->cc2538_rfcore_xreg_rssistat.XREG_RSSISTATbits.RSSI_VALID);
|
||||
result = BOOLEAN(RFCORE->XREG_FSMSTAT1bits.CCA);
|
||||
cc2538_off();
|
||||
return result;
|
||||
}
|
||||
else {
|
||||
RFCORE_WAIT_UNTIL(RFCORE->cc2538_rfcore_xreg_rssistat.XREG_RSSISTATbits.RSSI_VALID);
|
||||
return BOOLEAN(RFCORE->XREG_FSMSTAT1bits.CCA);
|
||||
}
|
||||
}
|
||||
|
||||
void cc2538_init(void)
|
||||
{
|
||||
const init_pair_t *pair;
|
||||
|
||||
for (pair = init_table; pair->reg_addr != NULL; pair++) {
|
||||
*pair->reg_addr = pair->value;
|
||||
}
|
||||
|
||||
cc2538_set_tx_power(CC2538_RF_POWER_DEFAULT);
|
||||
cc2538_set_chan(CC2538_RF_CHANNEL_DEFAULT);
|
||||
cc2538_set_pan(CC2538_RF_PANID_DEFAULT);
|
||||
cc2538_set_addr_long(cc2538_get_eui64_primary());
|
||||
|
||||
/* Select the observable signals (maximum of three) */
|
||||
RFCORE_XREG_RFC_OBS_CTRL0 = tx_active;
|
||||
RFCORE_XREG_RFC_OBS_CTRL1 = rx_active;
|
||||
RFCORE_XREG_RFC_OBS_CTRL2 = ffctrl_fifo;
|
||||
|
||||
/* Select output pins for the three observable signals */
|
||||
#ifdef BOARD_OPENMOTE_CC2538
|
||||
CCTEST_OBSSEL0 = 0; /* PC0 = USB_SEL */
|
||||
CCTEST_OBSSEL1 = 0; /* PC1 = N/C */
|
||||
CCTEST_OBSSEL2 = 0; /* PC2 = N/C */
|
||||
CCTEST_OBSSEL3 = 0; /* PC3 = USER_BUTTON */
|
||||
CCTEST_OBSSEL4 = OBSSEL_EN | rfc_obs_sig0; /* PC4 = RED_LED */
|
||||
CCTEST_OBSSEL5 = 0; /* PC5 = ORANGE_LED */
|
||||
CCTEST_OBSSEL6 = OBSSEL_EN | rfc_obs_sig1; /* PC6 = YELLOW_LED */
|
||||
CCTEST_OBSSEL7 = OBSSEL_EN | rfc_obs_sig2; /* PC7 = GREEN_LED */
|
||||
#else
|
||||
/* Assume BOARD_CC2538DK (or similar). */
|
||||
CCTEST_OBSSEL0 = OBSSEL_EN | rfc_obs_sig0; /* PC0 = LED_1 (red) */
|
||||
CCTEST_OBSSEL1 = OBSSEL_EN | rfc_obs_sig1; /* PC1 = LED_2 (yellow) */
|
||||
CCTEST_OBSSEL2 = OBSSEL_EN | rfc_obs_sig2; /* PC2 = LED_3 (green) */
|
||||
CCTEST_OBSSEL3 = 0; /* PC3 = LED_4 (red) */
|
||||
CCTEST_OBSSEL4 = 0; /* PC4 = BTN_L */
|
||||
CCTEST_OBSSEL5 = 0; /* PC5 = BTN_R */
|
||||
CCTEST_OBSSEL6 = 0; /* PC6 = BTN_UP */
|
||||
CCTEST_OBSSEL7 = 0; /* PC7 = BTN_DN */
|
||||
#endif /* BOARD_OPENMOTE_CC2538 */
|
||||
|
||||
if (SYS_CTRL->I_MAP) {
|
||||
NVIC_SetPriority(RF_RXTX_ALT_IRQn, RADIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(RF_RXTX_ALT_IRQn);
|
||||
|
||||
NVIC_SetPriority(RF_ERR_ALT_IRQn, RADIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(RF_ERR_ALT_IRQn);
|
||||
}
|
||||
else {
|
||||
NVIC_SetPriority(RF_RXTX_IRQn, RADIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(RF_RXTX_IRQn);
|
||||
|
||||
NVIC_SetPriority(RF_ERR_IRQn, RADIO_IRQ_PRIO);
|
||||
NVIC_EnableIRQ(RF_ERR_IRQn);
|
||||
}
|
||||
|
||||
/* Flush the receive and transmit FIFOs */
|
||||
RFCORE_SFR_RFST = ISFLUSHTX;
|
||||
RFCORE_SFR_RFST = ISFLUSHRX;
|
||||
|
||||
cc2538_on();
|
||||
}
|
||||
|
||||
bool cc2538_is_on(void)
|
||||
{
|
||||
return RFCORE->XREG_FSMSTAT1bits.RX_ACTIVE || RFCORE->XREG_FSMSTAT1bits.TX_ACTIVE;
|
||||
}
|
||||
|
||||
void cc2538_off(void)
|
||||
{
|
||||
/* Wait for ongoing TX to complete (e.g. this could be an outgoing ACK) */
|
||||
RFCORE_WAIT_UNTIL(RFCORE->XREG_FSMSTAT1bits.TX_ACTIVE == 0);
|
||||
|
||||
/* Flush RX FIFO */
|
||||
RFCORE_SFR_RFST = ISFLUSHRX;
|
||||
|
||||
/* Don't turn off if we are off as this will trigger a Strobe Error */
|
||||
if (RFCORE_XREG_RXENABLE != 0) {
|
||||
RFCORE_SFR_RFST = ISRFOFF;
|
||||
}
|
||||
}
|
||||
|
||||
bool cc2538_on(void)
|
||||
{
|
||||
/* Flush RX FIFO */
|
||||
RFCORE_SFR_RFST = ISFLUSHRX;
|
||||
|
||||
/* Enable/calibrate RX */
|
||||
RFCORE_SFR_RFST = ISRXON;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void cc2538_setup(cc2538_rf_t *dev)
|
||||
{
|
||||
netdev2_t *netdev = (netdev2_t *)dev;
|
||||
|
||||
netdev->driver = &cc2538_rf_driver;
|
||||
|
||||
mutex_init(&dev->mutex);
|
||||
|
||||
cc2538_init();
|
||||
}
|
||||
255
cpu/cc2538/radio/cc2538_rf_getset.c
Normal file
255
cpu/cc2538/radio/cc2538_rf_getset.c
Normal file
@ -0,0 +1,255 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd.
|
||||
* Copyright (C) 2015 Loci Controls Inc.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Getter and setter functions for the cc2538_rf driver
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
* @author Ian Martin <ian@locicontrols.com>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cc2538_rf.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
/* static const __flash uint8_t? */
|
||||
static const uint8_t power_lut[NUM_POWER_LEVELS] = {
|
||||
0, /**< -24 dBm */
|
||||
7, /**< -23 dBm */
|
||||
15, /**< -22 dBm */
|
||||
22, /**< -21 dBm */
|
||||
29, /**< -20 dBm */
|
||||
37, /**< -19 dBm */
|
||||
44, /**< -18 dBm */
|
||||
51, /**< -17 dBm */
|
||||
59, /**< -16 dBm */
|
||||
66, /**< -15 dBm */
|
||||
77, /**< -14 dBm */
|
||||
88, /**< -13 dBm */
|
||||
93, /**< -12 dBm */
|
||||
98, /**< -11 dBm */
|
||||
106, /**< -10 dBm */
|
||||
114, /**< -9 dBm */
|
||||
125, /**< -8 dBm */
|
||||
136, /**< -7 dBm */
|
||||
141, /**< -6 dBm */
|
||||
145, /**< -5 dBm */
|
||||
153, /**< -4 dBm */
|
||||
161, /**< -3 dBm */
|
||||
169, /**< -2 dBm */
|
||||
176, /**< -1 dBm */
|
||||
182, /**< 0 dBm */
|
||||
197, /**< 1 dBm */
|
||||
205, /**< 2 dBm */
|
||||
213, /**< 3 dBm */
|
||||
225, /**< 4 dBm */
|
||||
237, /**< 5 dBm */
|
||||
246, /**< 6 dBm */
|
||||
255, /**< 7 dBm */
|
||||
};
|
||||
|
||||
uint64_t cc2538_get_addr_long(void)
|
||||
{
|
||||
uint64_t addr = RFCORE_FFSM_EXT_ADDR0;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR1;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR2;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR3;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR4;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR5;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR6;
|
||||
addr <<= 8;
|
||||
addr |= RFCORE_FFSM_EXT_ADDR7;
|
||||
return addr;
|
||||
}
|
||||
|
||||
uint16_t cc2538_get_addr_short(void)
|
||||
{
|
||||
return (RFCORE_FFSM_SHORT_ADDR0 << 8) | RFCORE_FFSM_SHORT_ADDR1;
|
||||
}
|
||||
|
||||
unsigned int cc2538_get_chan(void)
|
||||
{
|
||||
return IEEE802154_FREQ2CHAN(CC2538_MIN_FREQ + RFCORE_XREG_FREQCTRL);
|
||||
}
|
||||
|
||||
uint64_t cc2538_get_eui64_primary(void)
|
||||
{
|
||||
/*
|
||||
* The primary EUI-64 seems to be written to memory in a non-sequential
|
||||
* byte order, with both 4-byte halves of the address flipped.
|
||||
*/
|
||||
uint64_t eui64 = ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[4];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[5];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[6];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[7];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[0];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[1];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[2];
|
||||
eui64 <<= 8;
|
||||
eui64 |= ((uint8_t*)CC2538_EUI64_LOCATION_PRI)[3];
|
||||
return eui64;
|
||||
}
|
||||
|
||||
bool cc2538_get_monitor(void)
|
||||
{
|
||||
return NOT(RFCORE->XREG_FRMFILT0bits.FRAME_FILTER_EN);
|
||||
}
|
||||
|
||||
uint16_t cc2538_get_pan(void)
|
||||
{
|
||||
return (RFCORE_FFSM_PAN_ID1 << 8) | RFCORE_FFSM_PAN_ID0;
|
||||
}
|
||||
|
||||
int cc2538_get_tx_power(void)
|
||||
{
|
||||
int index;
|
||||
int best_index = 0;
|
||||
int best_delta = INT_MAX;
|
||||
int txpower;
|
||||
|
||||
txpower = RFCORE_XREG_TXPOWER & 0xff;
|
||||
|
||||
for (index = 0; index < NUM_POWER_LEVELS; index++) {
|
||||
int delta = ABS_DIFF(power_lut[index], txpower);
|
||||
|
||||
if (delta < best_delta) {
|
||||
best_delta = delta;
|
||||
best_index = index;
|
||||
}
|
||||
}
|
||||
|
||||
return OUTPUT_POWER_MIN + best_index;
|
||||
}
|
||||
|
||||
void cc2538_set_addr_long(uint64_t addr)
|
||||
{
|
||||
RFCORE_FFSM_EXT_ADDR0 = addr >> (7 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR1 = addr >> (6 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR2 = addr >> (5 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR3 = addr >> (4 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR4 = addr >> (3 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR5 = addr >> (2 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR6 = addr >> (1 * 8);
|
||||
RFCORE_FFSM_EXT_ADDR7 = addr >> (0 * 8);
|
||||
}
|
||||
|
||||
void cc2538_set_addr_short(uint16_t addr)
|
||||
{
|
||||
RFCORE_FFSM_SHORT_ADDR1 = addr;
|
||||
RFCORE_FFSM_SHORT_ADDR0 = addr >> 8;
|
||||
}
|
||||
|
||||
void cc2538_set_chan(unsigned int chan)
|
||||
{
|
||||
DEBUG("%s(%u): Setting channel to ", __FUNCTION__, chan);
|
||||
|
||||
if (chan < IEEE802154_MIN_CHANNEL) {
|
||||
chan = IEEE802154_MIN_CHANNEL;
|
||||
}
|
||||
else if (chan > IEEE802154_MAX_CHANNEL) {
|
||||
chan = IEEE802154_MAX_CHANNEL;
|
||||
}
|
||||
|
||||
DEBUG("%i (range %i-%i)\n", chan, IEEE802154_MIN_CHANNEL,
|
||||
IEEE802154_MAX_CHANNEL);
|
||||
|
||||
cc2538_set_freq(IEEE802154_CHAN2FREQ(chan));
|
||||
}
|
||||
|
||||
void cc2538_set_freq(unsigned int MHz)
|
||||
{
|
||||
DEBUG("%s(%u): Setting frequency to ", __FUNCTION__, freq);
|
||||
|
||||
if (MHz < IEEE802154_MIN_FREQ) {
|
||||
MHz = IEEE802154_MIN_FREQ;
|
||||
}
|
||||
else if (MHz > IEEE802154_MAX_FREQ) {
|
||||
MHz = IEEE802154_MAX_FREQ;
|
||||
}
|
||||
|
||||
DEBUG("%i (range %i-%i)\n", MHz, IEEE802154_MIN_FREQ, IEEE802154_MAX_FREQ);
|
||||
RFCORE_XREG_FREQCTRL = MHz - CC2538_MIN_FREQ;
|
||||
}
|
||||
|
||||
void cc2538_set_monitor(bool mode)
|
||||
{
|
||||
RFCORE->XREG_FRMFILT0bits.FRAME_FILTER_EN = NOT(mode);
|
||||
}
|
||||
|
||||
void cc2538_set_state(cc2538_rf_t *dev, netopt_state_t state)
|
||||
{
|
||||
switch (state) {
|
||||
case NETOPT_STATE_OFF:
|
||||
case NETOPT_STATE_SLEEP:
|
||||
cc2538_off();
|
||||
dev->state = state;
|
||||
break;
|
||||
|
||||
case NETOPT_STATE_RX:
|
||||
case NETOPT_STATE_IDLE:
|
||||
if (!cc2538_is_on()) {
|
||||
cc2538_on();
|
||||
RFCORE_WAIT_UNTIL(RFCORE->XREG_FSMSTAT0bits.FSM_FFCTRL_STATE > FSM_STATE_RX_CALIBRATION);
|
||||
}
|
||||
dev->state = state;
|
||||
break;
|
||||
|
||||
case NETOPT_STATE_TX:
|
||||
dev->state = NETOPT_STATE_IDLE;
|
||||
break;
|
||||
|
||||
case NETOPT_STATE_RESET:
|
||||
cc2538_off();
|
||||
cc2538_on();
|
||||
RFCORE_WAIT_UNTIL(RFCORE->XREG_FSMSTAT0bits.FSM_FFCTRL_STATE > FSM_STATE_RX_CALIBRATION);
|
||||
dev->state = NETOPT_STATE_IDLE;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void cc2538_set_pan(uint16_t pan)
|
||||
{
|
||||
RFCORE_FFSM_PAN_ID0 = pan;
|
||||
RFCORE_FFSM_PAN_ID1 = pan >> 8;
|
||||
}
|
||||
|
||||
void cc2538_set_tx_power(int dBm)
|
||||
{
|
||||
DEBUG("%s(%i): Setting TX power to ", __FUNCTION__, dBm);
|
||||
|
||||
if (dBm < OUTPUT_POWER_MIN) {
|
||||
dBm = OUTPUT_POWER_MIN;
|
||||
}
|
||||
else if (dBm > OUTPUT_POWER_MAX) {
|
||||
dBm = OUTPUT_POWER_MAX;
|
||||
}
|
||||
|
||||
DEBUG("%idBm (range %i-%i dBm)\n", OUTPUT_POWER_MIN, OUTPUT_POWER_MAX);
|
||||
RFCORE_XREG_TXPOWER = power_lut[dBm - OUTPUT_POWER_MIN];
|
||||
}
|
||||
138
cpu/cc2538/radio/cc2538_rf_internal.c
Normal file
138
cpu/cc2538/radio/cc2538_rf_internal.c
Normal file
@ -0,0 +1,138 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Implementation of driver internal functions
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "sched.h"
|
||||
#include "thread.h"
|
||||
|
||||
#include "cc2538.h"
|
||||
#include "cc2538_rf.h"
|
||||
#include "cc2538_rf_netdev.h"
|
||||
#include "cc2538_rf_internal.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
void isr_rfcoreerr(void)
|
||||
{
|
||||
uint_fast8_t flags;
|
||||
|
||||
/* Latch and clear the interrupt status */
|
||||
flags = RFCORE_SFR_RFERRF;
|
||||
RFCORE_SFR_RFERRF = 0;
|
||||
|
||||
/* These conditions shouldn't happen if the driver is working properly */
|
||||
RFCORE_ASSERT(NOT(flags & RXUNDERF));
|
||||
RFCORE_ASSERT(NOT(flags & TXOVERF));
|
||||
RFCORE_ASSERT(NOT(flags & TXUNDERF));
|
||||
|
||||
/* Fail in case of miscallaneous unexpected error conditions */
|
||||
RFCORE_ASSERT(NOT(flags & STROBE_ERR));
|
||||
|
||||
DEBUG("%s(): RFERRF=0x%02x.\n", __FUNCTION__, flags);
|
||||
|
||||
/* Flush the receive FIFO in case of a receive overflow */
|
||||
if (flags & RXOVERF) {
|
||||
DEBUG("%s(): RXOVERF detected!\n", __FUNCTION__);
|
||||
RFCORE_FLUSH_RECEIVE_FIFO();
|
||||
}
|
||||
|
||||
/* Flush the receive FIFO in case of a receive overflow */
|
||||
if (flags & NLOCK) {
|
||||
/* The frequency synthesizer failed to achieve lock after time-out, or
|
||||
* lock is lost during reception. The receiver must be restarted to clear
|
||||
* this error situation. */
|
||||
DEBUG("%s(): NLOCK detected!\n", __FUNCTION__);
|
||||
RFCORE_FLUSH_RECEIVE_FIFO();
|
||||
}
|
||||
}
|
||||
|
||||
void isr_rfcorerxtx(void)
|
||||
{
|
||||
RFCORE_SFR_RFIRQF0 = 0;
|
||||
RFCORE_SFR_RFIRQF1 = 0;
|
||||
|
||||
_irq_handler();
|
||||
|
||||
if (sched_context_switch_request) {
|
||||
thread_yield();
|
||||
}
|
||||
}
|
||||
|
||||
uint_fast8_t rfcore_read_byte(void)
|
||||
{
|
||||
RFCORE_ASSERT(RFCORE_XREG_RXFIFOCNT > 0);
|
||||
return RFCORE_SFR_RFDATA;
|
||||
}
|
||||
|
||||
uint_fast8_t rfcore_peek_rx_fifo(int idx)
|
||||
{
|
||||
RFCORE_ASSERT(idx >= 0 && idx < CC2538_RF_FIFO_SIZE);
|
||||
return *(uint_fast8_t *)(CC2538_RX_FIFO_ADDR + 4 * idx);
|
||||
}
|
||||
|
||||
void rfcore_read_fifo(void *buf, uint_fast8_t len)
|
||||
{
|
||||
uint_fast8_t n;
|
||||
|
||||
RFCORE_ASSERT(len <= RFCORE_XREG_RXFIFOCNT);
|
||||
|
||||
for (n = 0; n < len; n++) {
|
||||
GET_BYTE(buf, n) = RFCORE_SFR_RFDATA;
|
||||
}
|
||||
}
|
||||
|
||||
void rfcore_strobe(uint_fast8_t instr)
|
||||
{
|
||||
RFCORE_SFR_RFST = instr;
|
||||
}
|
||||
|
||||
void rfcore_write_byte(uint_fast8_t byte)
|
||||
{
|
||||
RFCORE_ASSERT(RFCORE_XREG_TXFIFOCNT < CC2538_RF_FIFO_SIZE);
|
||||
RFCORE_SFR_RFDATA = byte;
|
||||
}
|
||||
|
||||
void rfcore_poke_tx_fifo(int idx, uint_fast8_t byte)
|
||||
{
|
||||
RFCORE_ASSERT(idx >= 0 && idx < CC2538_RF_FIFO_SIZE);
|
||||
*(uint_fast8_t *)(CC2538_TX_FIFO_ADDR + 4 * idx) = byte;
|
||||
}
|
||||
|
||||
void rfcore_write_fifo(const void *buf, uint_fast8_t len)
|
||||
{
|
||||
uint_fast8_t n;
|
||||
|
||||
RFCORE_ASSERT(len <= CC2538_RF_FIFO_SIZE - RFCORE_XREG_TXFIFOCNT);
|
||||
|
||||
for (n = 0; n < len; n++) {
|
||||
RFCORE_SFR_RFDATA = GET_BYTE(buf, n);
|
||||
}
|
||||
}
|
||||
|
||||
bool RFCORE_ASSERT_failure(const char *expr, const char *func, int line)
|
||||
{
|
||||
#if (DEVELHELP || ENABLE_DEBUG)
|
||||
DEBUG_PRINT("RFCORE_ASSERT(%s) failed at line %u in %s()!\n", expr, line, func);
|
||||
DEBUG_PRINT(" RFCORE_SFR_RFERRF = 0x%02x\n", (unsigned int)RFCORE_SFR_RFERRF);
|
||||
#endif
|
||||
|
||||
return false;
|
||||
}
|
||||
384
cpu/cc2538/radio/cc2538_rf_netdev.c
Normal file
384
cpu/cc2538/radio/cc2538_rf_netdev.c
Normal file
@ -0,0 +1,384 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_cc2538
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Netdev adaption for the CC2538 RF driver
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <errno.h>
|
||||
|
||||
#include "net/gnrc.h"
|
||||
#include "net/netdev2.h"
|
||||
|
||||
#include "cc2538_rf.h"
|
||||
#include "cc2538_rf_netdev.h"
|
||||
#include "cc2538_rf_internal.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
#define _MAX_MHR_OVERHEAD (25)
|
||||
|
||||
static int _get(netdev2_t *dev, netopt_t opt, void *value, size_t max_len);
|
||||
static int _set(netdev2_t *dev, netopt_t opt, void *value, size_t value_len);
|
||||
static int _send(netdev2_t *netdev, const struct iovec *vector, int count);
|
||||
static int _recv(netdev2_t *netdev, char *buf, int len, void *info);
|
||||
static void _isr(netdev2_t *netdev);
|
||||
static int _init(netdev2_t *dev);
|
||||
|
||||
const netdev2_driver_t cc2538_rf_driver = {
|
||||
.get = _get,
|
||||
.set = _set,
|
||||
.send = _send,
|
||||
.recv = _recv,
|
||||
.isr = _isr,
|
||||
.init = _init,
|
||||
};
|
||||
|
||||
/* Reference pointer for the IRQ handler */
|
||||
static netdev2_t *_dev;
|
||||
|
||||
void _irq_handler(void)
|
||||
{
|
||||
if (_dev->event_callback) {
|
||||
_dev->event_callback(_dev, NETDEV2_EVENT_ISR);
|
||||
}
|
||||
}
|
||||
|
||||
static int _get(netdev2_t *netdev, netopt_t opt, void *value, size_t max_len)
|
||||
{
|
||||
cc2538_rf_t *dev = (cc2538_rf_t *)netdev;
|
||||
|
||||
if (dev == NULL) {
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
switch (opt) {
|
||||
case NETOPT_AUTOACK:
|
||||
if (RFCORE->XREG_FRMCTRL0bits.AUTOACK) {
|
||||
*((netopt_enable_t *)value) = NETOPT_ENABLE;
|
||||
}
|
||||
else {
|
||||
*((netopt_enable_t *)value) = NETOPT_DISABLE;
|
||||
}
|
||||
return sizeof(netopt_enable_t);
|
||||
|
||||
case NETOPT_CHANNEL_PAGE:
|
||||
if (max_len < sizeof(uint16_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
/* This tranceiver only supports page 0 */
|
||||
*((uint16_t *)value) = 0;
|
||||
return sizeof(uint16_t);
|
||||
|
||||
case NETOPT_DEVICE_TYPE:
|
||||
if (max_len < sizeof(uint16_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
*((uint16_t *) value) = NETDEV2_TYPE_IEEE802154;
|
||||
return sizeof(uint16_t);
|
||||
|
||||
case NETOPT_IS_CHANNEL_CLR:
|
||||
if (cc2538_channel_clear()) {
|
||||
*((netopt_enable_t *)value) = NETOPT_ENABLE;
|
||||
}
|
||||
else {
|
||||
*((netopt_enable_t *)value) = NETOPT_DISABLE;
|
||||
}
|
||||
return sizeof(netopt_enable_t);
|
||||
|
||||
case NETOPT_IS_WIRED:
|
||||
return -ENOTSUP;
|
||||
|
||||
case NETOPT_MAX_PACKET_SIZE:
|
||||
if (max_len < sizeof(int16_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
*((uint16_t *)value) = CC2538_RF_MAX_DATA_LEN - _MAX_MHR_OVERHEAD;
|
||||
return sizeof(uint16_t);
|
||||
|
||||
case NETOPT_PROMISCUOUSMODE:
|
||||
if (cc2538_get_monitor()) {
|
||||
*((netopt_enable_t *)value) = NETOPT_ENABLE;
|
||||
}
|
||||
else {
|
||||
*((netopt_enable_t *)value) = NETOPT_DISABLE;
|
||||
}
|
||||
return sizeof(netopt_enable_t);
|
||||
|
||||
case NETOPT_STATE:
|
||||
if (max_len < sizeof(netopt_state_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
*((netopt_state_t *)value) = dev->state;
|
||||
return sizeof(netopt_state_t);
|
||||
|
||||
case NETOPT_TX_POWER:
|
||||
if (max_len < sizeof(int16_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
*((uint16_t *)value) = cc2538_get_tx_power();
|
||||
return sizeof(uint16_t);
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
int res;
|
||||
|
||||
if (((res = netdev2_ieee802154_get((netdev2_ieee802154_t *)netdev, opt, value,
|
||||
max_len)) >= 0) || (res != -ENOTSUP)) {
|
||||
return res;
|
||||
}
|
||||
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
static int _set(netdev2_t *netdev, netopt_t opt, void *value, size_t value_len)
|
||||
{
|
||||
cc2538_rf_t *dev = (cc2538_rf_t *)netdev;
|
||||
int res = -ENOTSUP;
|
||||
|
||||
if (dev == NULL) {
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
switch (opt) {
|
||||
case NETOPT_ADDRESS:
|
||||
if (value_len > sizeof(uint16_t)) {
|
||||
res = -EOVERFLOW;
|
||||
}
|
||||
else {
|
||||
cc2538_set_addr_short(*((uint16_t*)value));
|
||||
}
|
||||
break;
|
||||
|
||||
case NETOPT_ADDRESS_LONG:
|
||||
if (value_len > sizeof(uint64_t)) {
|
||||
res = -EOVERFLOW;
|
||||
}
|
||||
else {
|
||||
cc2538_set_addr_long(*((uint64_t*)value));
|
||||
}
|
||||
break;
|
||||
|
||||
case NETOPT_AUTOACK:
|
||||
RFCORE->XREG_FRMCTRL0bits.AUTOACK = ((bool *)value)[0];
|
||||
res = sizeof(netopt_enable_t);
|
||||
break;
|
||||
|
||||
case NETOPT_CHANNEL:
|
||||
if (value_len != sizeof(uint16_t)) {
|
||||
res = -EINVAL;
|
||||
}
|
||||
else {
|
||||
uint8_t chan = ((uint8_t *)value)[0];
|
||||
if (chan < IEEE802154_MIN_CHANNEL ||
|
||||
chan > IEEE802154_MAX_CHANNEL) {
|
||||
res = -EINVAL;
|
||||
}
|
||||
else {
|
||||
cc2538_set_chan(chan);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case NETOPT_CHANNEL_PAGE:
|
||||
/* This tranceiver only supports page 0 */
|
||||
if (value_len != sizeof(uint16_t) ||
|
||||
*((uint16_t *)value) != 0 ) {
|
||||
res = -EINVAL;
|
||||
}
|
||||
else {
|
||||
res = sizeof(uint16_t);
|
||||
}
|
||||
break;
|
||||
|
||||
case NETOPT_IS_WIRED:
|
||||
return -ENOTSUP;
|
||||
|
||||
case NETOPT_NID:
|
||||
if (value_len > sizeof(uint16_t)) {
|
||||
res = -EOVERFLOW;
|
||||
}
|
||||
else {
|
||||
cc2538_set_pan(*((uint16_t *)value));
|
||||
}
|
||||
break;
|
||||
|
||||
case NETOPT_PROMISCUOUSMODE:
|
||||
cc2538_set_monitor(((bool *)value)[0]);
|
||||
res = sizeof(netopt_enable_t);
|
||||
break;
|
||||
|
||||
case NETOPT_STATE:
|
||||
if (value_len > sizeof(netopt_state_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
cc2538_set_state(dev, *((netopt_state_t *)value));
|
||||
res = sizeof(netopt_state_t);
|
||||
break;
|
||||
|
||||
case NETOPT_TX_POWER:
|
||||
if (value_len > sizeof(int16_t)) {
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
cc2538_set_tx_power(*((int16_t *)value));
|
||||
res = sizeof(uint16_t);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (res == -ENOTSUP) {
|
||||
res = netdev2_ieee802154_set((netdev2_ieee802154_t *)netdev, opt,
|
||||
value, value_len);
|
||||
}
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
static int _send(netdev2_t *netdev, const struct iovec *vector, int count)
|
||||
{
|
||||
int pkt_len = 0;
|
||||
|
||||
cc2538_rf_t *dev = (cc2538_rf_t *) netdev;
|
||||
mutex_lock(&dev->mutex);
|
||||
|
||||
/* Flush TX FIFO */
|
||||
RFCORE_SFR_RFST = ISFLUSHTX;
|
||||
|
||||
/* The first byte of the TX FIFO must be the packet length,
|
||||
but we don't know what it is yet. Write a null byte to the
|
||||
start of the FIFO, so we can come back and update it later */
|
||||
rfcore_write_byte(0);
|
||||
|
||||
for (int i = 0; i < count; i++) {
|
||||
pkt_len += vector[i].iov_len;
|
||||
|
||||
if (pkt_len > CC2538_RF_MAX_DATA_LEN) {
|
||||
DEBUG("cc2538_rf: packet too large (%u > %u)\n",
|
||||
pkt_len, CC2538_RF_MAX_DATA_LEN);
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
|
||||
rfcore_write_fifo(vector[i].iov_base, vector[i].iov_len);
|
||||
}
|
||||
|
||||
/* Set first byte of TX FIFO to the packet length */
|
||||
rfcore_poke_tx_fifo(0, pkt_len + CC2538_AUTOCRC_LEN);
|
||||
|
||||
RFCORE_SFR_RFST = ISTXON;
|
||||
mutex_unlock(&dev->mutex);
|
||||
|
||||
return pkt_len;
|
||||
}
|
||||
|
||||
static int _recv(netdev2_t *netdev, char *buf, int len, void *info)
|
||||
{
|
||||
cc2538_rf_t *dev = (cc2538_rf_t *) netdev;
|
||||
size_t pkt_len;
|
||||
|
||||
mutex_lock(&dev->mutex);
|
||||
|
||||
if (buf == NULL) {
|
||||
/* GNRC wants to know how much data we've got for it */
|
||||
pkt_len = rfcore_read_byte();
|
||||
|
||||
/* If the value of the first byte of the RX FIFO does not correspond
|
||||
to the amount of data received, then drop the packet. */
|
||||
if (pkt_len != RFCORE_XREG_RXFIFOCNT) {
|
||||
RFCORE_SFR_RFST = ISFLUSHRX;
|
||||
mutex_unlock(&dev->mutex);
|
||||
return -EOVERFLOW;
|
||||
}
|
||||
|
||||
if (len > 0) {
|
||||
/* GNRC wants us to drop the packet */
|
||||
RFCORE_SFR_RFST = ISFLUSHRX;
|
||||
}
|
||||
|
||||
mutex_unlock(&dev->mutex);
|
||||
return pkt_len - IEEE802154_FCS_LEN;
|
||||
}
|
||||
else {
|
||||
/* GNRC is expecting len bytes of data */
|
||||
pkt_len = len;
|
||||
}
|
||||
|
||||
rfcore_read_fifo(buf, pkt_len);
|
||||
|
||||
if (info != NULL) {
|
||||
netdev2_ieee802154_rx_info_t *radio_info = info;
|
||||
radio_info->rssi = rfcore_read_byte();
|
||||
|
||||
/* This is not strictly 802.15.4 compliant, since according to
|
||||
the CC2538 documentation, this value will tend between ~50
|
||||
for the lowest quality link detectable by the receiver, and
|
||||
~110 for the highest. The IEEE 802.15.4 spec mandates that
|
||||
this value be between 0-255, with 0 as lowest quality and
|
||||
255 as the highest. FIXME. */
|
||||
radio_info->lqi = rfcore_read_byte() & 0x7F;
|
||||
}
|
||||
|
||||
RFCORE_SFR_RFST = ISFLUSHRX;
|
||||
mutex_unlock(&dev->mutex);
|
||||
|
||||
return pkt_len;
|
||||
}
|
||||
|
||||
static void _isr(netdev2_t *netdev)
|
||||
{
|
||||
netdev->event_callback(netdev, NETDEV2_EVENT_RX_COMPLETE);
|
||||
}
|
||||
|
||||
static int _init(netdev2_t *netdev)
|
||||
{
|
||||
cc2538_rf_t *dev = (cc2538_rf_t *) netdev;
|
||||
_dev = netdev;
|
||||
|
||||
mutex_lock(&dev->mutex);
|
||||
|
||||
uint16_t pan = cc2538_get_pan();
|
||||
uint16_t chan = cc2538_get_chan();
|
||||
uint16_t addr_short = cc2538_get_addr_short();
|
||||
uint64_t addr_long = cc2538_get_addr_long();
|
||||
|
||||
/* Initialise netdev2_ieee802154_t struct */
|
||||
netdev2_ieee802154_set((netdev2_ieee802154_t *)netdev, NETOPT_NID,
|
||||
&pan, sizeof(pan));
|
||||
netdev2_ieee802154_set((netdev2_ieee802154_t *)netdev, NETOPT_CHANNEL,
|
||||
&chan, sizeof(chan));
|
||||
netdev2_ieee802154_set((netdev2_ieee802154_t *)netdev, NETOPT_ADDRESS,
|
||||
&addr_short, sizeof(addr_short));
|
||||
netdev2_ieee802154_set((netdev2_ieee802154_t *)netdev, NETOPT_ADDRESS_LONG,
|
||||
&addr_long, sizeof(addr_long));
|
||||
|
||||
cc2538_set_state(dev, NETOPT_STATE_IDLE);
|
||||
|
||||
/* set default protocol */
|
||||
#ifdef MODULE_GNRC_SIXLOWPAN
|
||||
dev->netdev.proto = GNRC_NETTYPE_SIXLOWPAN;
|
||||
#elif MODULE_GNRC
|
||||
dev->netdev.proto = GNRC_NETTYPE_UNDEF;
|
||||
#endif
|
||||
|
||||
mutex_unlock(&dev->mutex);
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -53,7 +53,7 @@ WEAK_DEFAULT void isr_timer1_chan1(void);
|
||||
WEAK_DEFAULT void isr_timer2_chan0(void);
|
||||
WEAK_DEFAULT void isr_timer2_chan1(void);
|
||||
WEAK_DEFAULT void isr_comp(void);
|
||||
WEAK_DEFAULT void isr_rfcoretx(void);
|
||||
WEAK_DEFAULT void isr_rfcorerxtx(void);
|
||||
WEAK_DEFAULT void isr_rfcoreerr(void);
|
||||
WEAK_DEFAULT void isr_icepick(void);
|
||||
WEAK_DEFAULT void isr_flash(void);
|
||||
@ -117,7 +117,7 @@ ISR_VECTORS const void *interrupt_vector[] = {
|
||||
(void*) isr_timer2_chan0, /* 39 Timer 2 subtimer A */
|
||||
(void*) isr_timer2_chan1, /* 40 Timer 2 subtimer B */
|
||||
(void*) isr_comp, /* 41 Analog Comparator 0 */
|
||||
(void*) isr_rfcoretx, /* 42 RFCore Rx/Tx */
|
||||
(void*) isr_rfcorerxtx, /* 42 RFCore Rx/Tx */
|
||||
(void*) isr_rfcoreerr, /* 43 RFCore Error */
|
||||
(void*) isr_icepick, /* 44 IcePick */
|
||||
(void*) isr_flash, /* 45 FLASH Control */
|
||||
|
||||
@ -205,6 +205,11 @@ void auto_init(void)
|
||||
auto_init_cc110x();
|
||||
#endif
|
||||
|
||||
#ifdef MODULE_CC2538_RF
|
||||
extern void auto_init_cc2538_rf(void);
|
||||
auto_init_cc2538_rf();
|
||||
#endif
|
||||
|
||||
#ifdef MODULE_XBEE
|
||||
extern void auto_init_xbee(void);
|
||||
auto_init_xbee();
|
||||
|
||||
65
sys/auto_init/netif/auto_init_cc2538_rf.c
Normal file
65
sys/auto_init/netif/auto_init_cc2538_rf.c
Normal file
@ -0,0 +1,65 @@
|
||||
/*
|
||||
* Copyright (C) 2016 MUTEX NZ Ltd
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
* @ingroup auto_init_gnrc_netif
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Auto initialization for the cc2538 network interface
|
||||
*
|
||||
* @author Aaron Sowry <aaron@mutex.nz>
|
||||
*/
|
||||
|
||||
#ifdef MODULE_CC2538_RF
|
||||
|
||||
#include "net/gnrc/netdev2.h"
|
||||
#include "net/gnrc/netdev2/ieee802154.h"
|
||||
|
||||
#include "cc2538_rf.h"
|
||||
|
||||
#define ENABLE_DEBUG 0
|
||||
#include "debug.h"
|
||||
|
||||
/**
|
||||
* @brief Define stack parameters for the MAC layer thread
|
||||
* @{
|
||||
*/
|
||||
#define CC2538_MAC_STACKSIZE (THREAD_STACKSIZE_DEFAULT)
|
||||
#define CC2538_MAC_PRIO (THREAD_PRIORITY_MAIN - 4)
|
||||
|
||||
static cc2538_rf_t cc2538_rf_dev;
|
||||
static gnrc_netdev2_t gnrc_adpt;
|
||||
static char _cc2538_rf_stack[CC2538_MAC_STACKSIZE];
|
||||
|
||||
void auto_init_cc2538_rf(void)
|
||||
{
|
||||
int res;
|
||||
|
||||
DEBUG("Initializing CC2538 radio...\n");
|
||||
cc2538_setup(&cc2538_rf_dev);
|
||||
res = gnrc_netdev2_ieee802154_init(&gnrc_adpt,
|
||||
(netdev2_ieee802154_t *)&cc2538_rf_dev);
|
||||
|
||||
if (res < 0) {
|
||||
DEBUG("Error initializing CC2538 radio device!\n");
|
||||
}
|
||||
else {
|
||||
gnrc_netdev2_init(_cc2538_rf_stack,
|
||||
CC2538_MAC_STACKSIZE,
|
||||
CC2538_MAC_PRIO,
|
||||
"cc2538_rf",
|
||||
&gnrc_adpt);
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
typedef int dont_be_pedantic;
|
||||
#endif /* MODULE_CC2538_RF */
|
||||
/** @} */
|
||||
Loading…
x
Reference in New Issue
Block a user